Allow specific frames to collide
Some contact is part of the job. A gripper has to touch the object it grasps. A vision-based obstacle detector mounted on an arm will see the arm as an obstacle. Two adjacent links in a simplified kinematic model may register as overlapping even though the real hardware does not. In each of these cases, the motion planner’s default rejection of any frame-on-frame contact blocks plans that should succeed.
CollisionSpecification tells the planner which pairs of frames are allowed
to touch. Use it to unblock planning for contact you have already accounted
for elsewhere.
Before you start
- A configured arm (or other frame-producing component) and a working motion service.
- You know which frames are being flagged. Plan failures that mention “collision detected” include the frame names; read them carefully.
- For the arm-detects-itself case, a camera that produces obstacle detections (a vision service + camera pair).
- If you are migrating from MoveIt’s self-filter or body padding
mechanism,
CollisionSpecificationis Viam’s equivalent.
The basic pattern
A CollisionSpecification is a list of allowed frame pairs; you build one,
wrap it in a Constraints object, and pass it to Move. Everything else on
this page is either specific use cases for this pattern or troubleshooting
when a frame name does not match.
from viam.services.motion import MotionClient
from viam.proto.service.motion import Constraints, CollisionSpecification
from viam.proto.common import PoseInFrame, Pose
motion_service = MotionClient.from_robot(machine, "builtin")
# Allow the gripper to contact the object it is picking up.
collision_spec = CollisionSpecification(
allows=[
CollisionSpecification.AllowedFrameCollisions(
frame1="my-gripper",
frame2="target-object",
),
],
)
constraints = Constraints(collision_specification=[collision_spec])
destination = PoseInFrame(
reference_frame="world",
pose=Pose(x=300, y=200, z=400, o_x=0, o_y=0, o_z=-1, theta=0),
)
await motion_service.move(
component_name="my-arm",
destination=destination,
constraints=constraints,
)
import (
"go.viam.com/rdk/motionplan"
"go.viam.com/rdk/services/motion"
)
// Allow the gripper to contact the object it is picking up.
constraints := &motionplan.Constraints{
CollisionSpecification: []motionplan.CollisionSpecification{
{
Allows: []motionplan.CollisionSpecificationAllowedFrameCollisions{
{Frame1: "my-gripper", Frame2: "target-object"},
},
},
},
}
_, err = motionService.Move(ctx, motion.MoveReq{
ComponentName: "my-arm",
Destination: destination,
Constraints: constraints,
})
The planner still checks every other pair of frames for collisions.
Listing one pair in CollisionSpecification does not disable collision
checking in general.
Hierarchical matching
Frame names in AllowedFrameCollisions match hierarchically. Naming my-arm
covers every link in the arm’s kinematics (my-arm:base_link,
my-arm:upper_arm_link, my-arm:forearm_link, and so on) plus any origin
geometry you configured. Naming my-arm:upper_arm_link covers only that one
link.
frame1 = "my-arm"matches every link ofmy-arm:my-arm:base_link,my-arm:upper_arm_link,my-arm:forearm_link, and so on.frame1 = "my-arm:upper_arm_link"matches only the upper arm link.- Names that do not match any known geometry produce an error that lists the available geometry names, which is often the fastest way to find the right name.
For most allow-list use cases, the parent component name ("my-arm",
"my-gripper") is what you want. Use a specific link name only when you
know the exact sub-frame and other sub-frames must continue to be
collision-checked.
Use case: arm detects itself through a vision service
The single most common reason to reach for CollisionSpecification: an
arm with an onboard or overhead camera feeds a vision service that
reports 3D obstacles, and the arm appears in the camera’s view. The
obstacle detection sees the arm as an obstacle, the planner sees the arm
colliding with itself, and motion halts.
- Look at the plan failure. The collision pair will include your arm’s
frame and a vision-detected obstacle frame (usually named after the
detector, for example
my-vision:detection-0). - Add a
CollisionSpecificationthat allows the arm to collide with the detection frames. In practice, this usually means allowing the arm to collide with anything the camera detects:
collision_spec = CollisionSpecification(
allows=[
CollisionSpecification.AllowedFrameCollisions(
frame1="my-arm",
frame2="my-vision",
),
],
)
constraints := &motionplan.Constraints{
CollisionSpecification: []motionplan.CollisionSpecification{
{
Allows: []motionplan.CollisionSpecificationAllowedFrameCollisions{
{Frame1: "my-arm", Frame2: "my-vision"},
},
},
},
}
- Re-run the motion. If the arm still fails on a real obstacle the camera reported, the collision was legitimate, and you need to address the motion target or obstacle geometry rather than expanding the allow list.
This is Viam’s equivalent of MoveIt’s self-filter or body padding. Instead of filtering camera data, you tell the planner that specific overlaps are expected.
Use case: gripper grasping an object
A grasp requires contact between the gripper and the object. Without a
CollisionSpecification allowing it, the planner rejects the final approach
as a collision. Allow the gripper-object pair and the plan completes.
collision_spec = CollisionSpecification(
allows=[
CollisionSpecification.AllowedFrameCollisions(
frame1="my-gripper",
frame2="target-object",
),
],
)
After the grasp, if you want to move the gripper plus its held object
as one unit, attach the object to the gripper frame system through
WorldState.transforms on subsequent Move requests. See
Define obstacles: passive objects attached to a component
for the permanent-attachment pattern.
Use case: adjacent arm links whose geometries overlap
Some kinematic models have simplified collision geometry that causes adjacent links to register as colliding in certain joint configurations, even though the real hardware does not. If you are sure the overlap is a modeling artifact and not a real collision:
collision_spec = CollisionSpecification(
allows=[
CollisionSpecification.AllowedFrameCollisions(
frame1="my-arm:upper_arm_link",
frame2="my-arm:forearm_link",
),
],
)
Be conservative here. Self-collision errors are often legitimate and silencing them can mask real hardware problems.
Verify the change
- Plan the motion that was failing. It should succeed.
- Plan a motion you expect to fail for other reasons (target inside an unrelated obstacle, target outside reach). The planner should still reject those.
- Visually confirm the motion in the 3D scene tab before running on hardware. See Debug a motion plan.
Troubleshooting
What’s next
- Configure motion constraints: the other three constraint types (Linear, Orientation, Pseudolinear).
- Define obstacles: the obstacle geometry that the planner checks against.
- Debug a motion plan: visualize frame overlaps in the 3D scene.
Was this page helpful?
Glad to hear it! If you have any other feedback please let us know:
We're sorry about that. To help us improve, please tell us what we can do better:
Thank you!