Skip to main content
Version: 9

Migrate Collision Object Behaviors

MoveIt Pro 9.4 replaces the legacy GraspableObject-based collision object Behaviors with a unified, moveit_msgs-based set. The old Behaviors still run but are deprecated and will be removed in a future major version. Update your Objectives to the replacements below so they keep working once the old Behaviors are gone.

Behavior mapping

Deprecated BehaviorReplacement
ModifyObjectInPlanningSceneAddCollisionBox / AddCollisionCylinder / AddCollisionSphere / AddCollisionMesh, AddCollisionObject for a prebuilt CollisionObject, or MoveCollisionObject to re-pose an existing object
AddVirtualObjectToPlanningSceneA shape-specific AddCollision* Behavior plus SetCollisionRule
CreateCollisionObjectFromSolidPrimitiveA shape-specific AddCollision* Behavior, or AddCollisionObject
CreateSolidPrimitiveBoxAddCollisionBox
RemoveCollisionObjectFromPlanningSceneRemoveCollisionObject
SetupMTCUpdateObjectCollisionRuleSetupMTCSetCollisionRule
SetupMTCUpdateGroupCollisionRuleSetupMTCSetCollisionRule
SetupMTCIgnoreCollisionsBetweenObjectsSetupMTCSetCollisionRule
SetupMTCAttachObjectSetupMTCAttachObjectByID
SetupMTCDetachObjectSetupMTCDetachObjectByID

How the new Behaviors work

  • Each Behavior does one job: refer to an object by a plain-text id, give a shape its dimensions and a pose, and it is added to the scene in one step, with no GraspableObject conversion.
  • Every non-MTC scene Behavior exposes an optional planning_scene port. Left unwired, the Behavior reads and updates the live planning scene. Wired to a blackboard variable, it reads the scene from that variable, applies the change, and writes it back, without touching the live scene, so you can build up a scene in memory and plan against it before committing.
  • Every operation has both a direct form and a matching MTC stage. Collision rules and object moves, which were previously only possible as MTC stages, now also have direct Behaviors.

Add a collision object

The legacy flow built a shape as a GraspableObject and added it with ModifyObjectInPlanningScene:

<Control ID="Sequence">
<Action ID="CreateStampedPose" reference_frame="grasp_link" position_xyz="0;0;0.1" stamped_pose="{pose}" />
<Action ID="CreateGraspableObject" object_id="box" pose="{pose}" dx="0.3" dy="0.3" dz="0.3" generate_front_face="false" generate_side_faces="false" generate_top_face="false" cuboid_object="{graspable_object}" />
<Action ID="ModifyObjectInPlanningScene" apply_planning_scene_service="/apply_planning_scene" object="{graspable_object}" />
</Control>

AddCollisionBox builds the shape and applies it in one step:

<Control ID="Sequence">
<Action ID="CreateStampedPose" reference_frame="grasp_link" position_xyz="0;0;0.1" stamped_pose="{pose}" />
<Action ID="AddCollisionBox" object_id="box" dimensions="0.3;0.3;0.3" pose="{pose}" />
</Control>

AddCollisionCylinder (height, radius), AddCollisionSphere (radius), and AddCollisionMesh (mesh_file_path, scale) work the same way for their shape. CreateSolidPrimitiveBox and CreateCollisionObjectFromSolidPrimitive are no longer needed: pick the shape-specific Behavior, or build a moveit_msgs/CollisionObject yourself and apply it directly with AddCollisionObject:

<Action ID="AddCollisionObject" collision_object="{collision_object}" />

Add a virtual object

A virtual object blocks the robot but is allowed to overlap other virtual objects. The legacy flow produced a GraspableObject and added it with AddVirtualObjectToPlanningScene:

<Control ID="Sequence">
<Action ID="GetCurrentPlanningScene" planning_scene_msg="{planning_scene}" />
<Action ID="CreateStampedPose" reference_frame="world" position_xyz="-0.076413;0.97;0.42" stamped_pose="{table_pose}" />
<Action ID="CreateGraspableObject" object_id="virtual_table_top" pose="{table_pose}" dx="2" dy="1" dz="0.1" generate_front_face="true" generate_side_faces="true" generate_top_face="true" cuboid_object="{table_top}" />
<Action ID="AddVirtualObjectToPlanningScene" apply_planning_scene_service="/apply_planning_scene" object="{table_top}" planning_scene_msg="{planning_scene}" />
</Control>

Add the geometry directly with a shape Behavior:

<Control ID="Sequence">
<Action ID="CreateStampedPose" reference_frame="world" position_xyz="-0.076413;0.97;0.42" stamped_pose="{table_pose}" />
<Action ID="AddCollisionBox" object_id="virtual_table_top" dimensions="2;1;0.1" pose="{table_pose}" />
</Control>

Two differences to mind:

  • The legacy Behavior prepended virtual_ to the object id, so the scene object was virtual_table_top. The new Behaviors use the id exactly as written, so keep that full string anywhere you reference the object later.
  • The legacy Behavior automatically let each virtual object overlap every other virtual object while the robot still collided with all of them. To reproduce that, add one SetCollisionRule per pair of objects that should pass through each other:
<Action ID="SetCollisionRule" name_a="virtual_table_top" name_b="virtual_back_wall" allow_collision="true" />

Each of name_a and name_b must uniquely name a planning group, collision object, or robot link; if a name matches more than one, the Behavior fails.

Move a collision object

To re-pose an object, the legacy flow re-added it through ModifyObjectInPlanningScene. MoveCollisionObject updates the pose of an existing object by id:

<Action ID="MoveCollisionObject" object_id="box" pose="{new_pose}" />

Remove a collision object

The legacy Behavior needed the current planning scene fetched and wired into it:

<Control ID="Sequence">
<Action ID="GetCurrentPlanningScene" planning_scene_msg="{planning_scene}" />
<Action ID="RemoveCollisionObjectFromPlanningScene" object_id="box" planning_scene_msg="{planning_scene}" />
</Control>

RemoveCollisionObject fetches the scene itself, so the GetCurrentPlanningScene step is no longer needed. Removing an id that is not present is a no-op that returns success:

<Action ID="RemoveCollisionObject" object_id="box" />

Set collision rules during MTC planning

SetupMTCSetCollisionRule replaces all three legacy ACM stages with one string-based interface. name_a and name_b each name a planning group (which expands to its links with collision geometry), a collision object, or a robot link. Make sure your planning groups, collision objects, and links do not share names: if a name matches more than one of these, the Behavior fails. The legacy task:

<Control ID="Sequence">
<Action ID="InitializeMTCTask" task_id="place" task="{mtc_task}" />
<Action ID="SetupMTCCurrentState" task="{mtc_task}" />
<Action ID="SetupMTCUpdateGroupCollisionRule" group_name="manipulator" object_name="table" allow_collision="true" task="{mtc_task}" />
<Action ID="SetupMTCIgnoreCollisionsBetweenObjects" object_names="box_1;box_2;box_3" allow_collision="true" task="{mtc_task}" />
<Action ID="PlanMTCTask" task="{mtc_task}" solution="{mtc_solution}" />
</Control>

The same task with the unified stage. SetupMTCUpdateObjectCollisionRule also maps to SetupMTCSetCollisionRule, and a set of objects that were mutually allowed via one SetupMTCIgnoreCollisionsBetweenObjects becomes one SetupMTCSetCollisionRule per pair:

<Control ID="Sequence">
<Action ID="InitializeMTCTask" task_id="place" task="{mtc_task}" />
<Action ID="SetupMTCCurrentState" task="{mtc_task}" />
<Action ID="SetupMTCSetCollisionRule" name_a="manipulator" name_b="table" allow_collision="true" task="{mtc_task}" />
<Action ID="SetupMTCSetCollisionRule" name_a="box_1" name_b="box_2" allow_collision="true" task="{mtc_task}" />
<Action ID="SetupMTCSetCollisionRule" name_a="box_1" name_b="box_3" allow_collision="true" task="{mtc_task}" />
<Action ID="SetupMTCSetCollisionRule" name_a="box_2" name_b="box_3" allow_collision="true" task="{mtc_task}" />
<Action ID="PlanMTCTask" task="{mtc_task}" solution="{mtc_solution}" />
</Control>

The same interface is available outside an MTC task as the SetCollisionRule Behavior, which was not possible with the legacy Behaviors.

Attach and detach during MTC planning

The ID-based stages take an object_id and link_name instead of a GraspableObject and frame_id. The legacy attach stage:

<Control ID="Sequence">
<Action ID="InitializeMTCTask" task_id="pick" task="{mtc_task}" />
<Action ID="SetupMTCCurrentState" task="{mtc_task}" />
<Action ID="SetupMTCAttachObject" object="{graspable_object}" frame_id="grasp_link" task="{mtc_task}" />
<Action ID="PlanMTCTask" task="{mtc_task}" solution="{mtc_solution}" />
</Control>

The same task, referencing the object by its id:

<Control ID="Sequence">
<Action ID="InitializeMTCTask" task_id="pick" task="{mtc_task}" />
<Action ID="SetupMTCCurrentState" task="{mtc_task}" />
<Action ID="SetupMTCAttachObjectByID" object_id="box" link_name="grasp_link" task="{mtc_task}" />
<Action ID="PlanMTCTask" task="{mtc_task}" solution="{mtc_solution}" />
</Control>

SetupMTCDetachObjectByID replaces SetupMTCDetachObject the same way. For attaching static collision geometry outside an MTC task, use the AttachObject and DetachObject Behaviors. URDF-based objects keep their own AttachURDF / DetachURDF Behaviors, which track joint state and are unaffected by this change.