isaac_ros_cumotion_object_attachment#

Source code available on GitHub.

Object Attachment#

For automating pick-and-place tasks, integrating the geometry of the grasped object into motion planning is crucial for preventing collisions and ensuring smooth operation. The isaac_ros_cumotion_object_attachment package plays a key role in this process by attaching the object’s geometry to the robot’s collision spheres when the object is picked up. The object’s geometry is specified by the user through an action goal that includes the object’s shape, pose, and dimensions. The geometry is then approximated with collision spheres and incorporated into the robot’s kinematic description. By doing this, the grasped object avoids collisions with the environment, as demonstrated in the top and bottom panels of Figure 1-b, while also ensuring correct robot segmentation, as shown in the middle panel of Figure 1-b.

This module’s effectiveness is seen throughout the entire pick-and-place sequence on a physical robot. It handles the object’s geometry during the attachment phase, after which the planning modules move the robot to the desired location. Once the object is placed, the module detaches the geometry from the robot. If the object geometry is not taken into account, as shown in Figure 1-a, it can lead to failures in segmentation or collisions with the environment. These failures highlight the importance of integrating this module to avoid planning disruptions.

Figure 1: Object attachment

Figure 1: Motion planning and segmentation with and without accounting for grasped object geometry in cuMotion.#

The module performs the following steps in sequence:

  1. The user sends an AttachObject action goal that specifies the object’s shape, pose, and dimensions using a visualization_msgs/Marker message.

  2. Based on the object type (sphere, cuboid, or mesh), the node generates a set of collision spheres using the cuMotion collision sphere generation API.

  3. The collision spheres are added to the robot’s XRDF description and sent to the cuMotion planner via the SetRobotDescription service, incorporating the object into the robot’s collision spheres.

  4. When ESDF clearing is enabled, the object’s occupied voxels are cleared from the nvblox SDF (signed distance field), ensuring that the object itself is not treated as an obstacle by the planner.

Three object types are supported for generating the collision spheres for the attached object:

  • Sphere: For objects that can be approximated by a single sphere. Produces a single collision sphere based

    on the largest scale dimension.

  • Cuboid: For objects that can be bounded by a box. The node generates a cuboid mesh from the specified

    dimensions and uses cuMotion to produce collision spheres that fill the cuboid volume.

  • Object mesh: For use when detailed object information is available. The user provides a mesh file path

    (through the mesh_resource field) along with scale factors and pose; cuMotion generates collision spheres from the mesh vertices and triangles.

These steps ensure that cuMotion takes into account the geometry of grasped objects, enabling smooth and collision-free motion planning.

Usage#

The isaac_ros_cumotion_object_attachment package is designed to operate as part of the Isaac ROS Manipulation pipeline, where it is invoked automatically during pick-and-place workflows. Object attachment and detachment are managed by the behavior tree orchestration layer; no standalone launch or manual interaction with this package is required.

To use object attachment in a manipulation workflow, see the following reference workflows:

The object attachment node is launched as part of the cuMotion bringup and can be enabled or disabled through the enable_object_attachment parameter. When enabled, it is automatically integrated into the motion planning pipeline, and its behavior is configured through the behavior tree parameters in the workflow’s YAML configuration file.

Troubleshooting#

Isaac ROS Troubleshooting#

For solutions to problems with Isaac ROS, refer to troubleshooting.

API#

ObjectAttachmentNode#

This is a ROS 2 node that provides an action server for attaching and detaching objects to the robot’s collision spheres. The node generates collision spheres for the specified object geometry (sphere, cuboid, or mesh), updates the robot’s XRDF description through services, and optionally clears the object’s voxels from the nvblox ESDF.

Component plugin: nvidia::isaac_ros::cumotion::ObjectAttachmentNode

ROS Parameters#

ROS Parameter

Type

Default

Description

max_overshoot

double

0.05

Maximum distance (in meters) that collision spheres may extend beyond the object’s mesh surface. A larger value produces fewer, coarser spheres (faster collision checking, but less precise), while a smaller value produces more, tighter spheres (slower but more accurate). Must be non-negative.

clear_esdf_on_attach

bool

True

Whether to clear the ESDF voxels occupied by the object when it is attached to the robot. Enable this when nvblox is running and providing an ESDF world representation. When nvblox is not used, set to False to avoid waiting for the unavailable ESDF service.

object_esdf_clearing_padding

double list

[0.05, 0.05, 0.05]

Extra clearance [x, y, z] in meters added around the world-frame clearing region per side. For AABBs (cuboid and mesh objects), the full padding is added per side. For spheres, the maximum component is added to the clearing sphere radius. All elements must be non-negative.

esdf_reference_frame

string

'base_link'

Reference frame for ESDF clearing. Must match the global_frame parameter of the nvblox node.

esdf_visualize_when_clearing

bool

True

Whether to request nvblox to republish ESDF visualization after clearing the attached object’s voxels. Can be set to False to reduce overhead if visualization is not needed.

get_robot_description_service

string

'/cumotion/get_robot_description'

Name of the service for retrieving the robot’s URDF and XRDF description. Must match the corresponding service name in the cuMotion planner node.

set_robot_description_service

string

'/cumotion/set_robot_description'

Name of the service for updating the robot’s XRDF description with attached object spheres. Must match the corresponding service name in the cuMotion planner node.

ROS Topics Published#

ROS Topic

Interface

Description

object_sphere_markers

visualization_msgs/MarkerArray

Visualization markers for the collision spheres of the attached object. Markers are published on attach and cleared on detach.

ROS Services Requested#

ROS Service

Interface

Description

get_robot_description_service

isaac_ros_cumotion_interfaces/GetRobotDescription

Retrieves the robot’s current URDF and XRDF description. Called once on first attachment and cached for subsequent operations.

set_robot_description_service

isaac_ros_cumotion_interfaces/SetRobotDescription

Sends the updated XRDF (with or without attached object spheres) to the cuMotion planner. Called on both attach (with spheres) and detach (original XRDF restored).

nvblox_node/get_esdf_and_gradient

nvblox_msgs/EsdfAndGradients

Clears the attached object’s voxels from the nvblox ESDF. Only used when clear_esdf_on_attach is True. The clearing region is computed as an AABB (for cuboid and mesh objects) or a sphere (for sphere objects), with object_esdf_clearing_padding applied.

ROS Actions Advertised#

ROS Action

Interface

Description

attach_object

isaac_ros_cumotion_interfaces/AttachObject

Attaches or detaches an object to the robot’s collision spheres.

  • Goal:

    • bool attach_object: Set to True to attach the object; False to detach it.

    • visualization_msgs/Marker object_config: Configuration of the object to attach, including shape type, pose, scale, and mesh resource path. The node uses the integer type field from the visualization_msgs/Marker message to determine the object shape. Supported type values:

      • visualization_msgs::msg::Marker::SPHERE (integer value 2): Single collision sphere; scale defines the diameter along each axis (largest is used).

      • visualization_msgs::msg::Marker::CUBE (integer value 1): Cuboid object; scale defines the full dimensions (x, y, z) in meters.

      • visualization_msgs::msg::Marker::MESH_RESOURCE (integer value 10): Custom mesh; mesh_resource specifies an absolute file path (file:// prefix is optional; package:// is not supported), and scale defines per-axis scale factors applied to the mesh vertices.

      The Isaac ROS Manipulation behavior tree maps user-facing string names (SPHERE, CUBOID, CUSTOM_MESH) to these Marker integer constants automatically.

      The header.frame_id specifies the reference frame for the object pose. The pose field defines the object’s position and orientation in that frame.

  • Result:

    • string outcome: Description of the result (e.g., “Object successfully attached”).

  • Feedback:

    • string status: Real-time status updates during execution.