isaac_ros_cumotion#
Source code available on GitHub.
Motion Generation#
The cuMotion motion generation workflow is exposed to MoveIt 2 via the
isaac_ros_cumotion_moveit planning plugin. See the corresponding
quickstart.
In addition, this package also exposes motion generation and inverse kinematics capabilities via
ROS 2 actions/services as documented below.
Launching the cuMotion action server#
The action server is provided by the component
nvidia::isaac_ros::cumotion::CumotionPlanner and can be launched with:
ros2 launch isaac_ros_cumotion isaac_ros_cumotion.launch.py \
cumotion_action_server.xrdf_file_path:=/path/to/ROBOT.xrdf \
cumotion_action_server.urdf_file_path:=/path/to/ROBOT.urdf
API#
CumotionActionServer#
ROS Parameters#
Note
The package ships a reference configuration in
isaac_ros_cumotion/params/isaac_ros_cumotion_params.yaml. When launching via
isaac_ros_cumotion.launch.py, those values are used as the default launch arguments.
ROS Parameter |
Type |
Default |
Description |
|---|---|---|---|
|
|
|
Path to the URDF file used to build the robot model. |
|
|
|
Path to the XRDF file used to configure cuMotion (e.g., joint limits, default configuration). |
|
|
|
Speed scaling factor used when re-timing planned trajectories. |
|
|
|
Interpolation time step (seconds) used when sampling planned trajectories. |
|
|
|
If true, query an ESDF from nvblox. |
|
|
|
Whether ESDF updates are requested when planning (in addition to initial grid setup). |
|
|
|
nvblox ESDF query service name. |
|
|
|
If true, publish world-collision spheres on the |
|
|
|
If true, publish self-collision spheres on the |
|
|
|
If true, publish occupancy voxels for visualization. |
|
|
|
Voxel size (meters) used for voxel visualization. |
|
|
|
Maximum number of voxels published for visualization. |
|
|
|
If true, add an implicit ground plane obstacle to the world. |
|
|
|
Ground plane X dimension (meters). |
|
|
|
Ground plane Y dimension (meters). |
|
|
|
Ground plane thickness (meters). |
|
|
|
Z offset below the robot base frame (meters). |
|
|
|
Joint state topic used as the default start state. |
|
|
|
Enable more verbose cuMotion library logging. |
|
|
|
If false, the node respects MoveIt’s velocity/acceleration scaling factors in the request. |
|
|
|
Enable CUDA Multi-Process Service (MPS) configuration for the cuMotion process. |
|
|
|
CUDA MPS pipe directory used when |
|
|
|
CUDA MPS client priority used when |
|
|
|
CUDA MPS active thread percentage used when |
|
|
|
Optional MoveIt scene file used by the static planning scene workflow. |
|
|
|
Maximum number of 1-second wait attempts for the static planning scene service to become available. |
|
|
|
Service name the node calls at startup to request static collision objects. |
ROS Actions Advertised#
ROS Action |
Interface |
Description |
|---|---|---|
|
MoveIt-compatible planning action used by the MoveIt cuMotion plugin. |
|
|
cuMotion-native goal-set motion planning action. |
|
|
Collision-free IK action (optionally using ESDF updates / AABB clearing). |
ROS Services Advertised#
ROS Service |
Interface |
Description |
|---|---|---|
|
Returns the currently loaded URDF/XRDF. |
|
|
Updates the URDF/XRDF at runtime and re-initializes dependent components. |
ROS Topics Subscribed#
ROS Topic |
Interface |
Description |
|---|---|---|
|
Robot joint state used as the default start state. |
ROS Topics Published#
ROS Topic |
Interface |
Description |
|---|---|---|
|
Robot collision sphere visualization. Controlled by |
|
|
Planned trajectories for RViz visualization. |
|
|
Event-style notification when the robot description is updated. |
|
|
World occupancy voxels for visualization (enabled via |
ROS Services Requested#
ROS Service |
Interface |
Description |
|---|---|---|
|
Loads collision objects from a static scene source and provides them as MoveIt collision objects. |
|
|
ESDF query service used when |