API Reference and Configuration#
This page provides comprehensive API documentation and configuration parameter reference for the multi-object Pick and Place workflow. For step-by-step configuration instructions, refer to the Configuration Guide.
Action Interface#
Action Server: /multi_object_pick_and_place
Action Type: isaac_ros_manipulation_interfaces/action/MultiObjectPickAndPlace
Goal Parameters#
Parameter |
Type |
Description |
|---|---|---|
|
|
Target drop poses in the robot’s base frame. For |
|
|
Array of object class IDs to pick and place. For |
|
|
Execution mode: |
Result Values#
Value |
Description |
|---|---|
|
All specified objects were successfully picked and placed |
|
Some objects were successfully processed, others failed |
|
All objects failed to be processed successfully |
|
Operation was canceled, interrupted by stale detection timeout, or failed before completion |
|
Workflow still in progress |
Parameter Validation Rules#
Mode |
|
|
Validation |
|---|---|---|---|
|
Exactly 1 pose |
Must be empty array |
All detected objects go to single location |
|
1+ poses (equal to |
1+ class IDs (equal to |
Objects sorted by class to corresponding poses |
Usage Examples#
All objects to one location:
ros2 action send_goal /multi_object_pick_and_place isaac_ros_manipulation_interfaces/action/MultiObjectPickAndPlace \
'{target_poses: {header: {frame_id: "base_link"}, poses: [{position: {x: -0.25, y: 0.45, z: 0.50}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}]}, class_ids: [], mode: 0}'
Objects sorted by class to different locations:
ros2 action send_goal /multi_object_pick_and_place isaac_ros_manipulation_interfaces/action/MultiObjectPickAndPlace \
'{target_poses: {header: {frame_id: "base_link"}, poses: [{position: {x: -0.25, y: 0.50, z: 0.70}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}, {position: {x: -0.25, y: 0.40, z: 0.40}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}]}, class_ids: ["22", "3"], mode: 1}'
Multi-bin mode with three object types:
ros2 action send_goal /multi_object_pick_and_place isaac_ros_manipulation_interfaces/action/MultiObjectPickAndPlace \
'{target_poses: {header: {frame_id: "base_link"}, poses: [{position: {x: -0.25, y: 0.50, z: 0.70}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}, {position: {x: -0.25, y: 0.40, z: 0.40}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}, {position: {x: -0.25, y: 0.30, z: 0.60}, orientation: {w: 0.017994, x: -0.677772, y: 0.734752, z: 0.020993}}]}, class_ids: ["22", "3", "15"], mode: 1}'
Launch Interface#
Launch File: orchestration.launch.py
Launch Arguments#
Argument |
Type |
Default |
Description |
Usage Notes |
|---|---|---|---|---|
|
|
|
Path to behavior tree configuration file |
Contains action server names, retry limits, and behavior-specific parameters |
|
|
|
Path to blackboard configuration file |
Contains object definitions, drop poses, and workflow mode settings |
|
|
|
Enable ASCII tree display on terminal |
Useful for debugging behavior tree execution flow |
|
|
|
Enable manual stepping through behavior tree |
Allows step-by-step execution for debugging and development |
|
|
|
Set logging level ( |
Use |
Example Launch#
ros2 launch isaac_ros_manipulation_pick_and_place orchestration.launch.py \
behavior_tree_config_file:=my_config.yaml \
blackboard_config_file:=my_blackboard.yaml \
print_ascii_tree:=true \
log_level:=debug
Configuration Files#
The system uses two main configuration files for behavior tree parameters and blackboard initialization.
File |
Purpose |
Contains |
|---|---|---|
|
Behavior tree node configuration |
Action server names, retry limits, timeout settings, motion planning parameters |
|
Blackboard variable initialization |
Object definitions, drop poses, workflow modes, supported objects configuration |
Behavior Tree Parameters#
File: multi_object_pick_and_place_behavior_tree_params.yaml
This file configures the behavior tree nodes and their associated action servers, services, and parameters. The configuration follows the structure behavior_tree_params.multi_object_pick_and_place.<node_name>:
Parameter |
Type |
Default |
Description |
|---|---|---|---|
|
|
|
Service name for assigning names to detected objects |
|
|
|
Action server name for object attachment. Connects to the object attachment node’s action server. |
|
|
|
Object shape type for collision sphere generation. |
|
|
|
Object dimensions [x, y, z] in meters for |
|
|
|
Frame in which grasp poses were recorded using the Grasp Editor |
|
|
|
Frame aligned between the gripper fingertips, offset from |
|
|
|
Action server name for gripper control |
|
|
|
Gripper position for closed/grasping state |
|
|
|
Maximum effort for gripper closing |
|
|
|
Action server name for object detachment. Uses the same object attachment action server with |
|
|
|
Action server name for object detection requests |
|
|
|
Minimum confidence threshold for accepting detected objects. Set higher (closer to 1.0) if your object detection model predicts class IDs with high confidence |
|
|
|
Action server name for trajectory execution |
|
|
|
Index of trajectory to execute from planned trajectories |
|
|
|
URI for mesh resource used in interactive markers |
|
|
|
Reference frame for interactive marker placement |
|
|
|
End effector frame for interactive marker |
|
|
|
User reaction time in seconds. Time allowed for user to adjust the interactive marker in RViz to set the correct drop pose before system proceeds with default marker position |
|
|
|
Service name for adding mesh to objects |
|
|
|
Action server name for object selection requests |
|
|
|
Action server name for gripper control |
|
|
|
Gripper position for fully open state |
|
|
|
Maximum effort for gripper opening |
|
|
|
Action server name for cuMotion planning requests |
|
|
|
Reference frame for motion planning |
|
|
|
Time scaling factor for trajectory execution |
|
|
|
Approach offset distance [x, y, z] in meters |
|
|
|
Max deviation (m) from the line segment connecting the initial and final tool frame positions during the grasp segment. Set to a negative value to disable the path constraint (terminal target only). |
|
|
|
Max deviation (m) from the translation target at termination during the grasp segment. Set to a negative value to use the cuMotion default. |
|
|
|
Whether to constrain the tool frame orientation to be constant (matching the orientation at the initial c-space position) along the path during the grasp segment. |
|
|
|
Max deviation (rad) from the constant orientation at termination during the grasp segment. Set to a negative value to use the cuMotion default. |
|
|
|
Max deviation (rad) from the constant orientation along the path during the grasp segment. Set to a negative value to use the cuMotion default. |
|
|
|
Retract offset distance [x, y, z] in meters |
|
|
|
Max deviation (m) from the line segment connecting the initial and final tool frame positions during the retract segment. Set to a negative value to disable the path constraint (terminal target only). |
|
|
|
Max deviation (m) from the translation target at termination during the retract segment. Set to a negative value to use the cuMotion default. |
|
|
|
Whether to constrain the tool frame orientation to be constant (matching the orientation at the initial c-space position) along the path during the retract segment. |
|
|
|
Max deviation (rad) from the constant orientation at termination during the retract segment. Set to a negative value to use the cuMotion default. |
|
|
|
Max deviation (rad) from the constant orientation along the path during the retract segment. Set to a negative value to use the cuMotion default. |
|
|
|
Whether approach constraints are in goal frame |
|
|
|
Whether retract constraints are in goal frame |
|
|
|
Whether to update planning scene before planning |
|
|
|
World reference frame for planning |
|
|
|
Enables axis-aligned bounding-box clearing of the nvblox ESDF around the grasp
pose before planning. When |
|
|
|
ESDF clearing padding [x, y, z] in meters |
|
|
|
Shape type for AABB clearing. Options: |
|
|
|
Scale for AABB clearing shape [x, y, z] |
|
|
|
Action server name for cuMotion planning requests |
|
|
|
Reference frame for motion planning |
|
|
|
Time scaling factor for trajectory execution |
|
|
|
Whether to update planning scene before planning |
|
|
|
Shape type for AABB clearing. Options: |
|
|
|
Scale for AABB clearing shape [x, y, z] |
|
|
|
Enables axis-aligned bounding-box clearing of the nvblox ESDF around the drop
pose before planning. When |
|
|
|
ESDF clearing padding [x, y, z] in meters |
|
|
|
Action server name for object pose estimation requests |
|
|
|
The robot base frame used to express object poses and workspace bounds |
|
|
|
Camera frame ID used by the pose estimation server. Must match your |
|
|
|
Two 3D points defining the diagonal corners of a cuboid workspace bounds [x, y, z] in |
|
|
|
Whether to publish grasp poses for visualization in RViz. Set to |
|
|
|
Maximum retry attempts for motion planning operations. Increase if your motion planning is unreliable or prone to failures |
|
|
|
Maximum retry attempts for hardware controller access. Set based on confidence in your controller reliability |
|
|
|
Maximum retry attempts for object detection operations. Set based on confidence in your detection system reliability |
|
|
|
Maximum retry attempts for pose estimation operations. Set based on confidence in your pose estimation system reliability |
|
|
|
Maximum retry attempts for gripper control operations. Set based on confidence in your gripper system reliability |
|
|
|
Maximum retry attempts for object attachment operations. Set based on confidence in your algorithm’s ability to attach objects. |
|
|
|
Maximum time to wait for action/service servers during startup. Set to |
|
|
|
Maximum time to retry servers during execution when temporarily losing access to them |
|
|
|
Interval between server availability checks during operation (also determines logging frequency for server status) |
|
|
|
Expected workflow completion time in seconds. If this time is exceeded, current detection data will be discarded after the current object placement completes, and the system will perform new detections before proceeding |
|
|
|
List of arm controllers to activate. Configure to ensure required controllers are in active state during motion execution |
|
|
|
List of arm controllers to deactivate. Configure to ensure conflicting controllers are deactivated during motion execution |
|
|
|
Strictness for controller switching. Values: |
|
|
|
List of tool controllers to activate. Configure to ensure required controllers are in active state during gripper operations |
|
|
|
List of tool controllers to deactivate. Configure to ensure conflicting controllers are deactivated during gripper operations |
|
|
|
Strictness for controller switching. Values: |
|
|
|
Service name used to publish static planning scene objects at startup |
|
|
|
Path to a MoveIt |
Blackboard Parameters#
File: multi_object_pick_and_place_blackboard_params.yaml
This file initializes the behavior tree’s shared blackboard variables. The configuration follows the structure blackboard_params.<parameter_name>.
For conceptual understanding of how these blackboard variables work together and their relationships in the workflow architecture, refer to the Blackboard Reference.
Parameter |
Type |
Default |
Description |
|---|---|---|---|
|
|
|
Maximum number of objects that can have completed pose estimation. When this limit is reached, the pose estimation sub-tree will be blocked until objects are processed |
|
|
|
Enable interactive marker in RViz for drop pose selection. Overrides drop poses from blackboard config or action calls. Updates drop poses for all queued objects when marker changes, allowing real-time pose adjustment. Requires user to be proactive in setting pose |
|
|
|
Runtime variable for motion termination |
|
|
|
Safe home position [x, y, z, quaternion_x, quaternion_y, quaternion_z, quaternion_w]. Used as fallback location when object placement to designated drop pose fails |
|
|
|
Target drop poses where objects will be placed [x, y, z, quaternion_x, quaternion_y, quaternion_z, quaternion_w]. For single bin sorting: provide exactly 1 pose. For multi-bin sorting: provide multiple poses that match the number of |
|
|
|
Object class IDs that determine which objects go to which target poses. For single bin sorting: leave empty (all objects go to the same location). For multi-bin sorting: specify class IDs that correspond to each target pose. |
|
|
|
Execution mode: |
|
|
|
Runtime variable for currently selected object |
|
|
|
Runtime variable for actively manipulated object |
|
|
|
Runtime variable for target drop pose |
|
|
|
Runtime variable for RViz interactive marker pose |
|
|
|
Runtime cache for object detection information |
|
|
|
Runtime queue of objects for processing |
|
|
|
Overall workflow completion status using MultiObjectPickAndPlace.Result enum values: |
|
|
|
Human-readable progress report generated by |
|
Runtime queue |
Auto-initialized |
Real-time queue of individual object completion/failure messages for immediate action feedback (automatically managed by |
|
|
|
Detection model class ID (RT-DETR class ID or GroundingDINO prompt index). Must be configured carefully based on the specific objects being handled by the system |
|
|
|
Path to YAML file containing pre-computed grasp poses. Must be configured carefully based on the specific objects being handled by the system |
|
|
|
Path to object mesh file for collision planning. Must be configured carefully based on the specific objects being handled by the system |