[isaacsim.robot_motion.cumotion] cumotion#

Version: 1.0.1

Access to cuMotion planners under the isaacsim motion generation API.

Enable Extension#

The extension can be enabled (if not already) in one of the following ways:

Define the next entry as an application argument from a terminal.

APP_SCRIPT.(sh|bat) --enable isaacsim.robot_motion.cumotion

Define the next entry under [dependencies] in an experience (.kit) file or an extension configuration (extension.toml) file.

[dependencies]
"isaacsim.robot_motion.cumotion" = {}

Open the Window > Extensions menu in a running application instance and search for isaacsim.robot_motion.cumotion. Then, toggle the enable control button if it is not already active.

API#

Python API#

Configuration Loading

load_cumotion_robot

Load a cuMotion robot from URDF and XRDF files.

load_cumotion_supported_robot

Load a cuMotion robot for a supported robot.

CumotionRobot

Robot for cuMotion planning and control.

World Interface

CumotionWorldInterface

World interface for cuMotion collision checking and planning.

Motion Policies

RmpFlowController

Reactive motion policy controller using cuMotion's RMPflow algorithm.

Motion Planning

GraphBasedMotionPlanner

Graph-based motion planner using cuMotion for collision-free path planning.

Trajectory Generation

TrajectoryGenerator

Trajectory generator for creating smooth, time-optimal trajectories (not collision-aware).

TrajectoryOptimizer

Trajectory optimizer using cuMotion's Trajectory Optimizer algorithm.

CumotionTrajectory

Continuous-time trajectory for a robot using cuMotion.

Transform Utilities

isaacsim.robot_motion.cumotion.impl.utils.isaac_sim_to_cumotion_pose

Convert Isaac Sim pose to cuMotion pose in the robot base frame.

isaacsim.robot_motion.cumotion.impl.utils.isaac_sim_to_cumotion_translation

Convert Isaac Sim position to cuMotion position in robot base frame.

isaacsim.robot_motion.cumotion.impl.utils.isaac_sim_to_cumotion_rotation

Convert Isaac Sim orientation to cuMotion rotation in robot base frame.

isaacsim.robot_motion.cumotion.impl.utils.cumotion_to_isaac_sim_pose

Convert cuMotion pose in base frame to Isaac Sim pose in world frame.

isaacsim.robot_motion.cumotion.impl.utils.cumotion_to_isaac_sim_translation

Convert cuMotion position to Isaac Sim position in world frame.

isaacsim.robot_motion.cumotion.impl.utils.cumotion_to_isaac_sim_rotation

Convert cuMotion rotation to Isaac Sim orientation in world frame.


Configuration Loading#

load_cumotion_robot(
directory: Path | str,
urdf_filename: Path | str = 'robot.urdf',
xrdf_filename: Path | str = 'robot.xrdf',
) CumotionRobot#

Load a cuMotion robot from URDF and XRDF files.

Loads the robot description from the specified URDF and XRDF files and creates a robot object containing the robot description, kinematics solver, and controlled joint names.

Parameters:
  • directory – Path to the directory containing the robot configuration files.

  • urdf_filename – Name of the URDF file. Defaults to “robot.urdf”.

  • xrdf_filename – Name of the XRDF file. Defaults to “robot.xrdf”.

Returns:

Robot object containing all necessary data for cuMotion.

Raises:

Exception – If the URDF/XRDF files cannot be loaded or parsed.

Example

robot = load_cumotion_robot(
    directory="/path/to/franka",
    urdf_filename="robot.urdf",
    xrdf_filename="robot.xrdf"
)
load_cumotion_supported_robot(
robot_name: str,
) CumotionRobot#

Load a cuMotion robot for a supported robot.

Loads a pre-configured robot from the extension’s robot_configurations directory. This is a convenience function for commonly used robots that come packaged with the extension.

Parameters:

robot_name – Name of the robot (e.g., “franka”, “ur10”).

Returns:

Robot object for the specified robot.

Raises:

Exception – If the robot cannot be found or loaded.

Example

robot = load_cumotion_supported_robot("franka")
class CumotionRobot(
directory: Path,
robot_description: RobotDescription,
kinematics: Kinematics,
controlled_joint_names: list[str],
)#

Bases: object

Robot for cuMotion planning and control.

This dataclass encapsulates all the necessary data for a robot to be used with cuMotion, including the robot description, kinematics solver, and controlled joint names.

directory#

Path to the robot configuration directory containing URDF/XRDF files.

Type:

pathlib.Path

robot_description#

cuMotion robot description loaded from URDF/XRDF files.

Type:

_cumotion.RobotDescription

kinematics#

cuMotion kinematics solver for the robot.

Type:

_cumotion.Kinematics

controlled_joint_names#

List of joint names that are controlled by the planner.

Type:

list[str]

controlled_joint_names: list[str]#
directory: Path#
kinematics: Kinematics#
robot_description: RobotDescription#

World Interface#

class CumotionWorldInterface(
world_to_robot_base: tuple[warp.array, warp.array] | None = None,
visualize_debug_prims: bool = False,
visual_debug_enabled_prim_rgb: list[float] | None = None,
visual_debug_disabled_prim_rgb: list[float] | None = None,
visual_debug_prim_alpha: float = 0.3,
)#

Bases: WorldInterface

World interface for cuMotion collision checking and planning.

This class provides the bridge between Isaac Sim’s USD scene representation and cuMotion’s collision world. It manages obstacle registration, updates, and coordinate frame transformations between Isaac Sim (world frame) and cuMotion (robot base frame).

Parameters:
  • world_to_robot_base – Transform from world frame to robot base frame. Defaults to None (identity transform). This is a tuple of position and quaternion, where the quaternion is in the form (w, x, y, z).

  • visualize_debug_prims – Whether to create visual debug primitives for collision geometry. Defaults to False.

  • visual_debug_prim_rgb – RGB color for debug visualization. Defaults to None (red).

  • visual_debug_prim_alpha – Alpha transparency for debug visualization. Defaults to 0.3.

world_view#

cuMotion world view for collision queries.

Example

world_interface = CumotionWorldInterface(
    visualize_debug_prims=True,
    visual_debug_prim_rgb=[0.0, 1.0, 0.0],
    visual_debug_prim_alpha=0.5
)
add_capsules(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']],
radii: warp.array,
lengths: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add capsule obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each capsule.

  • axes – Orientation axis for each capsule.

  • radii – Capsule radii.

  • lengths – Capsule heights (excluding hemispherical caps).

  • scales – Local scale factors for each capsule.

  • safety_tolerances – Safety margin around each capsule.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each capsule.

Raises:

NotImplementedError – If not overridden by subclass.

add_cones(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']],
radii: warp.array,
lengths: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add cone obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each cone.

  • axes – Orientation axis for each cone.

  • radii – Cone base radii.

  • lengths – Cone heights.

  • scales – Local scale factors for each cone.

  • safety_tolerances – Safety margin around each cone.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each cone.

Raises:

NotImplementedError – If not overridden by subclass.

add_cubes(
prim_paths: list[str],
sizes: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add cube obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each cube.

  • sizes – Cube side lengths.

  • scales – Local scale factors for each cube.

  • safety_tolerances – Safety margin around each cube.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each cube.

Raises:

NotImplementedError – If not overridden by subclass.

add_cylinders(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']],
radii: warp.array,
lengths: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add cylinder obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each cylinder.

  • axes – Orientation axis for each cylinder.

  • radii – Cylinder radii.

  • lengths – Cylinder heights.

  • scales – Local scale factors for each cylinder.

  • safety_tolerances – Safety margin around each cylinder.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each cylinder.

Raises:

NotImplementedError – If not overridden by subclass.

add_meshes(
prim_paths: list[str],
points: list[warp.array],
face_vertex_indices: list[warp.array],
face_vertex_counts: list[warp.array],
normals: list[warp.array],
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add mesh obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each mesh.

  • points – Vertex positions for each mesh.

  • face_vertex_indices – Face vertex indices for each mesh.

  • face_vertex_counts – Number of vertices per face for each mesh.

  • normals – Face normals for each mesh.

  • scales – Local scale factors for each mesh.

  • safety_tolerances – Safety margin around each mesh.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each mesh.

Raises:

NotImplementedError – If not overridden by subclass.

add_oriented_bounding_boxes(
prim_paths: list[str],
centers: warp.array,
rotations: warp.array,
half_side_lengths: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add oriented bounding box obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each bounding box.

  • centers – Local center positions for each bounding box.

  • rotations – Local rotations as quaternions (w, x, y, z) for each bounding box.

  • half_side_lengths – Half extents along each axis for each bounding box.

  • scales – Local scale factors for each bounding box.

  • safety_tolerances – Safety margin around each bounding box.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each bounding box.

Raises:

NotImplementedError – If not overridden by subclass.

add_planes(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']],
lengths: warp.array,
widths: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add plane obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each plane.

  • axes – Normal axis for each plane.

  • lengths – Plane lengths.

  • widths – Plane widths.

  • scales – Local scale factors for each plane.

  • safety_tolerances – Safety margin around each plane.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each plane.

Raises:

NotImplementedError – If not overridden by subclass.

add_spheres(
prim_paths: list[str],
radii: warp.array,
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add sphere obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each sphere.

  • radii – Sphere radii.

  • scales – Local scale factors for each sphere.

  • safety_tolerances – Safety margin around each sphere.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each sphere.

Raises:

NotImplementedError – If not overridden by subclass.

add_triangulated_meshes(
prim_paths: list[str],
points: list[warp.array],
face_vertex_indices: list[warp.array],
scales: warp.array,
safety_tolerances: warp.array,
poses: tuple[warp.array, warp.array],
enabled_array: warp.array,
)#

Add triangulated mesh obstacles to the planning world.

Parameters:
  • prim_paths – USD prim paths for each mesh.

  • points – Vertex positions for each mesh.

  • face_vertex_indices – Triangle vertex indices for each mesh.

  • scales – Local scale factors for each mesh.

  • safety_tolerances – Safety margin around each mesh.

  • poses – Tuple of (positions, orientations) arrays.

  • enabled_array – Collision enabled state for each mesh.

Raises:

NotImplementedError – If not overridden by subclass.

get_world_to_robot_base_transform() tuple[warp.array, warp.array]#

Get the transform from world frame to robot base frame.

Returns the current transform that maps coordinates from the Isaac Sim world frame to the cuMotion robot base frame.

Returns:

Tuple of (position, quaternion) as warp arrays where position has shape (3,) and quaternion has shape (4,) in (w, x, y, z) format.

update_capsule_properties(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']] | None,
radii: wp.array | None,
lengths: wp.array | None,
)#

Update capsule-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of capsules to update.

  • axes – New orientation axes. Pass None to skip updating.

  • radii – New capsule radii. Pass None to skip updating.

  • lengths – New capsule heights. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_cone_properties(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']] | None,
radii: wp.array | None,
lengths: wp.array | None,
)#

Update cone-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of cones to update.

  • axes – New orientation axes. Pass None to skip updating.

  • radii – New cone base radii. Pass None to skip updating.

  • lengths – New cone heights. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_cube_properties(
prim_paths: list[str],
sizes: wp.array | None,
)#

Update cube-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of cubes to update.

  • sizes – New cube side lengths. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_cylinder_properties(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']] | None,
radii: wp.array | None,
lengths: wp.array | None,
)#

Update cylinder-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of cylinders to update.

  • axes – New orientation axes. Pass None to skip updating.

  • radii – New cylinder radii. Pass None to skip updating.

  • lengths – New cylinder heights. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_mesh_properties(
prim_paths: list[str],
points: list[warp.array] | None,
face_vertex_indices: list[warp.array] | None,
face_vertex_counts: list[warp.array] | None,
normals: list[warp.array] | None,
)#

Update mesh-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of meshes to update.

  • points – New vertex positions. Pass None to skip updating.

  • face_vertex_indices – New face vertex indices. Pass None to skip updating.

  • face_vertex_counts – New face vertex counts. Pass None to skip updating.

  • normals – New face normals. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_obstacle_enables(
prim_paths: list[str],
enabled_array: warp.array,
)#

Update the enabled/disabled state of tracked obstacles.

Enables or disables collision checking for obstacles that have already been added to the world. Disabled obstacles are ignored during collision checking.

Parameters:
  • prim_paths – List of prim paths identifying the obstacles to update.

  • enabled_array – Warp array of boolean values indicating enabled state, shape (N,) where N is the number of prim paths.

Raises:
  • RuntimeError – If any prim paths are not currently tracked.

  • ValueError – If input arrays have mismatched lengths or are empty.

update_obstacle_scales(
prim_paths: list[str],
scales: warp.array,
)#

Update local scales for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of obstacles to update.

  • scales – New local scale factors.

Raises:

NotImplementedError – If not overridden by subclass.

update_obstacle_transforms(
prim_paths: list[str],
poses: tuple[warp.array, warp.array],
)#

Update the world-to-object transforms for tracked obstacles.

Updates the poses of obstacles that have already been added to the world.

Parameters:
  • prim_paths – List of prim paths identifying the obstacles to update.

  • poses – Tuple of (positions, quaternions) where positions has shape (N, 3) and quaternions has shape (N, 4) in (w, x, y, z) format.

Raises:
  • RuntimeError – If any prim paths are not currently tracked.

  • ValueError – If input arrays have mismatched lengths or are empty.

update_obstacle_twists(
prim_paths: list[str],
poses: tuple[warp.array, warp.array],
)#

Update twist velocities for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of obstacles to update.

  • poses – Tuple of (linear velocities, angular velocities) arrays.

Raises:

NotImplementedError – If not overridden by subclass.

update_oriented_bounding_box_properties(
prim_paths: list[str],
centers: wp.array | None,
rotations: wp.array | None,
half_side_lengths: wp.array | None,
)#

Update oriented bounding box-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of bounding boxes to update.

  • centers – New local center positions. Pass None to skip updating.

  • rotations – New local rotations as quaternions (w, x, y, z). Pass None to skip updating.

  • half_side_lengths – New half extents. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_plane_properties(
prim_paths: list[str],
axes: list[Literal['X', 'Y', 'Z']] | None,
lengths: wp.array | None,
widths: wp.array | None,
)#

Update plane-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of planes to update.

  • axes – New normal axes. Pass None to skip updating.

  • lengths – New plane lengths. Pass None to skip updating.

  • widths – New plane widths. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_sphere_properties(
prim_paths: list[str],
radii: wp.array | None,
)#

Update sphere-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of spheres to update.

  • radii – New sphere radii. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_triangulated_mesh_properties(
prim_paths: list[str],
points: list[warp.array] | None,
face_vertex_indices: list[warp.array] | None,
)#

Update triangulated mesh-specific properties for existing obstacles.

Parameters:
  • prim_paths – USD prim paths of triangulated meshes to update.

  • points – New vertex positions. Pass None to skip updating.

  • face_vertex_indices – New triangle vertex indices. Pass None to skip updating.

Raises:

NotImplementedError – If not overridden by subclass.

update_world_to_robot_root_transforms(
poses: tuple[warp.array, warp.array],
)#

Update the transform from world frame to robot base frame.

cuMotion plans relative to the robot base frame. This method updates the base frame pose and recomputes all collider transforms in the base frame.

Parameters:

poses – Tuple of (positions, quaternions) where positions has shape (1, 3) and quaternions has shape (1, 4) in (w, x, y, z) format.

Raises:
  • ValueError – If the number of transforms is not exactly 1.

  • ValueError – If positions don’t have 3 elements.

  • ValueError – If quaternions don’t have 4 elements.

property world_view#

Get the world_view associated with the cumotion.World object


Motion Policies#

class RmpFlowController(
cumotion_robot: CumotionRobot,
cumotion_world_interface: CumotionWorldInterface,
robot_joint_space: list[str],
robot_site_space: list[str],
rmp_flow_configuration_filename: Path | str = 'rmp_flow.yaml',
tool_frame: str | None = None,
)#

Bases: BaseController

Reactive motion policy controller using cuMotion’s RMPflow algorithm.

RMPflow (Riemannian Motion Policies) is a reactive control algorithm that generates smooth, collision-free motions by combining multiple motion policies in task and configuration space. This controller continuously updates joint commands based on the desired targets.

Parameters:
  • cumotion_robot – Robot containing kinematics and joint information.

  • cumotion_world_interface – World interface providing collision geometry.

  • robot_joint_space – The full ordered joint-space of the controlled robot.

  • robot_site_space – The full ordered site-space of the controlled robot (used for validation of tool-frame name only).

  • rmp_flow_configuration_filename – Path to the RMPflow YAML configuration file. If a relative path is provided, it is resolved relative to cumotion_robot.directory. If an absolute path is provided, it is used as-is. Defaults to “rmp_flow.yaml”.

  • tool_frame – Name of the tool frame for end-effector control. Defaults to None, which uses the first tool frame defined in the robot description.

Example

controller = RmpFlowController(
    cumotion_robot=robot,
    cumotion_world_interface=world_interface,
    rmp_flow_configuration_filename="rmp_flow.yaml"
)
controller.reset(estimated_state, setpoint_state, t=0.0)
desired_state = controller.forward(estimated_state, setpoint_state, t=0.1)
forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Compute the desired joint action for the next time-step.

Evaluates the RMPflow controller to compute desired joint positions and velocities based on the current desired robot state and target attractors. The controller integrates the computed accelerations over time.

Parameters:
  • estimated_state – Current estimated state of the robot.

  • setpoint_state – Desired setpoint state containing target attractors. Can include joint positions, end-effector positions, and/or orientations. End-effector inputs must match the tool frame defined at initialization for this controller.

  • t – Current clock time (simulation or real).

  • **kwargs – Additional arguments for the controller.

Returns:

Robot state containing desired joint positions and velocities, or None if the controller is not initialized.

Example

desired_state = controller.forward(current_state, target_state, t=1.0)
if desired_state is not None:
    robot.set_dof_position_targets(
        desired_state.joints.positions,
        indices=[0],
        dof_indices=robot.get_joint_indices(desired_state.joints.names)
    )
get_rmp_flow_config() RmpFlowConfig#

Get the RMPflow configuration object.

Returns the underlying cuMotion configuration object, allowing users to modify controller parameters before initialization.

Returns:

The cuMotion RMPflow configuration object.

Example

config = controller.get_rmp_flow_config()
config.set_param("cspace_target_rmp/damping_gain", 0.9)
reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Reset the controller to a safe initial state.

Initializes the RMPflow controller and sets the internal state to match the current robot configuration. This should be called before running the controller for the first time.

Parameters:
  • estimated_state – Current estimated state of the robot.

  • setpoint_state – Initial setpoint state (currently unused).

  • t – Current clock time (simulation or real).

  • **kwargs – Additional arguments for the controller.

Returns:

True if reset was successful, False otherwise.

Example

success = controller.reset(current_state, None, t=0.0)
if success:
    print("Controller initialized successfully")

Motion Planning#

class GraphBasedMotionPlanner(
cumotion_robot: CumotionRobot,
cumotion_world_interface: CumotionWorldInterface,
tool_frame: str | None = None,
graph_planner_config_filename: Path | str | None = None,
)#

Bases: object

Graph-based motion planner using cuMotion for collision-free path planning.

This planner uses sampling-based algorithms (RRT variants) to find collision-free paths for robotic manipulators. It supports planning to configuration space targets, task space pose targets, and translation-only targets.

Parameters:
  • cumotion_robot – Robot configuration containing the robot description (URDF/XRDF) and configuration directory.

  • cumotion_world_interface – World interface providing collision geometry and world view.

  • tool_frame – Name of the tool frame to use for task space planning. Defaults to None, which uses the first tool frame defined in the robot description.

  • graph_planner_config_filename – Path to a YAML configuration file for the planner parameters. If a relative path is provided, it is resolved relative to cumotion_robot.directory. If an absolute path is provided, it is used as-is. Defaults to None, which uses default planner parameters.

Example

from isaacsim.robot_motion.cumotion import (
    CumotionRobot,
    CumotionWorldInterface,
    GraphBasedMotionPlanner,
)

robot_config = CumotionRobot(franka_directory)
world_interface = CumotionWorldInterface(robot_config)
planner = GraphBasedMotionPlanner(robot_config, world_interface)

# Plan to a joint configuration target
path = planner.plan_to_cspace_target(q_initial, q_target)
get_cumotion_robot() CumotionRobot#

Get the robot configuration.

Returns:

The robot configuration used by this planner.

get_graph_planner_config() MotionPlannerConfig#

Get the motion planner configuration.

Returns the underlying cuMotion configuration object, allowing users to modify planner parameters before planning.

Returns:

The cuMotion motion planner configuration object.

Example

config = planner.get_graph_planner_config()
config.set_param("max_iterations", cumotion.MotionPlannerConfig.ParamValue(1000))
plan_to_cspace_target(
q_initial: wp.array | np.ndarray | list[float],
q_final: wp.array | np.ndarray | list[float],
) Path | None#

Plan a collision-free path to a target joint configuration.

Uses graph-based planning (RRT) to find a collision-free path from the initial joint configuration to the target joint configuration in configuration space.

Parameters:
  • q_initial – Initial joint configuration.

  • q_final – Target joint configuration.

Returns:

Path object if a path was found, None otherwise.

Example

q_initial = [0.0, -0.5, 0.0, -2.0, 0.0, 1.5, 0.75]
q_target = [1.0, -0.3, 0.2, -1.8, 0.1, 1.2, 0.5]
path = planner.plan_to_cspace_target(q_initial, q_target)
if path is not None:
    trajectory = path.to_minimal_time_joint_trajectory()
plan_to_pose_target(
q_initial: wp.array | np.ndarray | list[float],
position: wp.array | np.ndarray | list[float],
orientation: wp.array | np.ndarray | list[float],
) Path | None#

Plan a collision-free path to a target pose (position + orientation) defined relative to the world frame.

Uses JtRRT (Jacobian-transpose RRT) to find a collision-free path from the initial joint configuration to a task space pose target. The orientation is fully constrained.

Parameters:
  • q_initial – Initial joint configuration.

  • position – Target position as [x, y, z] relative to world origin.

  • orientation – Target orientation as quaternion [w, x, y, z] or 3x3 rotation matrix relative to world frame.

Returns:

Path object if a path was found, None otherwise.

Raises:

ValueError – If orientation is not a valid quaternion (4 elements) or 3x3 rotation matrix.

Example

q_initial = [0.0, -0.5, 0.0, -2.0, 0.0, 1.5, 0.75]
position = [0.5, 0.2, 0.4]
orientation = [1.0, 0.0, 0.0, 0.0]  # wxyz quaternion (identity)
path = planner.plan_to_pose_target(q_initial, position, orientation)
plan_to_translation_target(
q_initial: wp.array | np.ndarray | list[float],
translation_target: wp.array | np.ndarray | list[float],
) Path | None#

Plan a collision-free path to a target position (translation only) defined relative to the world frame.

Uses JtRRT (Jacobian-transpose RRT) to find a collision-free path from the initial joint configuration to a task space translation target. The end-effector orientation is unconstrained, allowing the planner more flexibility in finding a valid path.

Parameters:
  • q_initial – Initial joint configuration.

  • translation_target – Target position as [x, y, z] relative to world frame origin.

Returns:

Path object if a path was found, None otherwise.

Example

q_initial = [0.0, -0.5, 0.0, -2.0, 0.0, 1.5, 0.75]
translation_target = [0.5, 0.2, 0.4]
path = planner.plan_to_translation_target(q_initial, translation_target)

Trajectory Generation#

class TrajectoryGenerator(
cumotion_robot: CumotionRobot,
robot_joint_space: list[str],
)#

Bases: object

Trajectory generator for creating smooth, time-optimal trajectories (not collision-aware).

This class provides utilities for generating smooth trajectories from discrete waypoints or path specifications. It handles conversion between configuration space and task space representations and generates time-optimal trajectories respecting joint velocity and acceleration limits.

Parameters:

cumotion_robot – Robot configuration containing kinematics and joint information.

Example

generator = TrajectoryGenerator(robot_config)
trajectory = generator.generate_trajectory_from_cspace_waypoints(
    waypoints=[[0, 0, 0], [1, 1, 1], [2, 2, 2]]
)
generate_trajectory_from_cspace_waypoints(
waypoints: wp.array | np.ndarray | list[list[float]],
times: wp.array | np.ndarray | list[float] | None = None,
interpolation_mode: cumotion.CSpaceTrajectoryGenerator.InterpolationMode | None = None,
) CumotionTrajectory | None#

Generate a trajectory from configuration space waypoints.

Creates a smooth time-optimal trajectory passing through the specified joint configuration waypoints. Optionally, specific timing for each waypoint can be provided, or an interpolation mode can be specified.

Parameters:
  • waypoints – Array of joint configurations, shape (n_waypoints, n_joints).

  • times – Optional time stamps for each waypoint. Defaults to None (automatic timing).

  • interpolation_mode – Interpolation method to use. Defaults to None (cuMotion default).

Returns:

Generated trajectory, or None if generation failed.

Raises:
  • RuntimeError – If waypoints is not two-dimensional.

  • RuntimeError – If fewer than 2 waypoints are provided.

  • RuntimeError – If waypoint dimension doesn’t match the number of controlled joints.

  • RuntimeError – If times is not one-dimensional.

  • RuntimeError – If the number of times doesn’t match the number of waypoints.

  • RuntimeError – If any time value is negative.

  • RuntimeError – If times are not strictly increasing.

Example

waypoints = [[0.0, -0.5, 0.0], [0.5, 0.0, 0.5], [1.0, 0.5, 1.0]]
trajectory = generator.generate_trajectory_from_cspace_waypoints(waypoints)

# With explicit timing
waypoints = [[0, 0], [1, 1], [2, 2]]
times = [0.0, 1.0, 2.0]
trajectory = generator.generate_trajectory_from_cspace_waypoints(
    waypoints, times
)
generate_trajectory_from_path_specification(
path_specification: CSpacePathSpec | TaskSpacePathSpec | CompositePathSpec,
tool_frame_name: str | None = None,
task_space_conversion_config: TaskSpacePathConversionConfig | None = None,
inverse_kinematics_config: IkConfig | None = None,
) CumotionTrajectory | None#

Generate a trajectory from a cuMotion path specification.

Converts the provided path specification (which may be in configuration space, task space, or composite) into a smooth time-optimal trajectory (not collision-aware). Task space paths are converted to configuration space using inverse kinematics.

Parameters:
  • path_specification – Path specification in cuMotion format (defined in base frame).

  • tool_frame_name – Name of the tool frame for task space planning. Defaults to None, which uses the first tool frame in the robot description.

  • task_space_conversion_config – Configuration for task space to configuration space conversion. Defaults to None.

  • inverse_kinematics_config – Configuration for inverse kinematics solver. Defaults to None.

Returns:

Generated trajectory, or None if generation failed.

Raises:

RuntimeError – If the path specification has fewer than 2 waypoints.

Example

path_spec = cumotion.create_cspace_path_spec(
    initial_cspace_position=np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]),
)
path_spec.add_cspace_waypoint(np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]))
path_spec.add_cspace_waypoint(np.array([2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0]))
trajectory = generator.generate_trajectory_from_path_specification(path_spec)
get_cspace_trajectory_generator() CSpaceTrajectoryGenerator#

Get the underlying cuMotion trajectory generator.

Returns the cuMotion generator object, allowing users to modify parameters directly.

Returns:

The cuMotion configuration space trajectory generator.

Example

gen = generator.get_cspace_trajectory_generator()
gen.set_velocity_limits(np.array([0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5]))

Note

Windows Support: The TrajectoryOptimizer is not currently available on Windows.

class TrajectoryOptimizer(
cumotion_robot: CumotionRobot,
robot_joint_space: list[str],
cumotion_world_interface: CumotionWorldInterface,
tool_frame: str | None = None,
trajectory_optimizer_config_filename: Path | str | None = None,
)#

Bases: object

Trajectory optimizer using cuMotion’s Trajectory Optimizer algorithm.

This class provides trajectory optimization capabilities. It generates smooth, collision-free trajectories to configuration space or task space targets by optimizing over trajectory costs including smoothness, collision avoidance, and goal achievement.

Parameters:
  • cumotion_robot – Robot configuration containing kinematics and joint information.

  • cumotion_world_interface – World interface providing collision geometry.

  • tool_frame – Name of the tool frame for task space planning. Defaults to None, which uses the first tool frame defined in the robot description.

  • trajectory_optimizer_config_filename – Path to the YAML configuration file. If a relative path is provided, it is resolved relative to cumotion_robot.directory. If an absolute path is provided, it is used as-is. Defaults to None (uses default parameters).

Example

optimizer = TrajectoryOptimizer(
    cumotion_robot=robot_config,
    cumotion_world_interface=world_interface,
)
# See cuMotion documentation for creating target specifications
trajectory = optimizer.plan_to_goal(q_initial, cspace_target)
get_cumotion_robot() CumotionRobot#

Get the robot configuration.

Returns:

The robot configuration used by this optimizer.

get_trajectory_optimizer_config() TrajectoryOptimizerConfig#

Get the trajectory optimizer configuration.

Returns the underlying cuMotion configuration object, allowing users to modify optimizer parameters before planning.

Returns:

The cuMotion trajectory optimizer configuration object.

Example

config = optimizer.get_trajectory_optimizer_config()
config.set_param("trajopt/pbo/num_iterations", cumotion.TrajectoryOptimizerConfig.ParamValue(100))
plan_to_goal(
initial_cspace_position: wp.array | np.ndarray | list[float],
goal: cumotion.TrajectoryOptimizer.CSpaceTarget | cumotion.TrajectoryOptimizer.TaskSpaceTargetGoalset | cumotion.TrajectoryOptimizer.TaskSpaceTarget,
) CumotionTrajectory | None#

Plan a trajectory to a specified goal.

Generates a smooth, collision-free trajectory from the initial configuration to the specified goal. The goal can be a configuration space target, task space target, or task space goalset.

Parameters:
  • initial_cspace_position – Initial joint configuration.

  • goal – Target goal specification (CSpaceTarget, TaskSpaceTarget, or TaskSpaceTargetGoalset). Note that all goals must be defined in the base frame.

Returns:

Optimized trajectory if successful, None if planning failed.

Raises:

ValueError – If goal type is not one of the supported types.

Example

# Configuration space target
q_initial = [0.0, -0.5, 0.0, -2.0, 0.0, 1.5, 0.75]
# See cuMotion documentation for constructing CSpaceTarget,
# TaskSpaceTarget, or TaskSpaceTargetGoalset objects
trajectory = optimizer.plan_to_goal(q_initial, target)
class CumotionTrajectory(
trajectory: cumotion.Trajectory,
robot_joint_space: list[str],
cumotion_robot: CumotionRobot,
device: wp.Device | None = None,
)#

Bases: Trajectory

Continuous-time trajectory for a robot using cuMotion.

This class wraps a cuMotion trajectory and provides the Isaac Sim trajectory interface for querying robot states at specific times. All trajectories start at time 0.0 and end after their duration.

Parameters:
  • trajectory – cuMotion trajectory object.

  • cumotion_robot – Robot configuration containing joint names and descriptions.

  • device – Warp device for computation. Defaults to None.

Example

trajectory = CumotionTrajectory(
    trajectory=cumotion_traj,
    cumotion_robot=robot_config
)
state = trajectory.get_target_state(time=1.0)
get_active_joints() list[str]#

Get the list of controlled joint names.

Returns:

List of joint names that are controlled in this trajectory.

get_target_state(
time: float,
) RobotState | None#

Get the target robot state at a specified time.

Returns joint positions and velocities for the robot at the given time along the trajectory. If the time is outside the trajectory domain, None is returned.

Parameters:

time – Time in trajectory at which to return joint targets.

Returns:

Robot state containing joint positions and velocities, or None if time is outside the trajectory domain.

Example:

state = trajectory.get_target_state(time=2.5)
if state is not None:
    print(state.joints.positions)
property duration: float#

Get the duration of the trajectory.

Returns:

Duration of the trajectory in seconds.


Transform Utilities#

The transform utilities provide coordinate conversion between Isaac Sim world frame and cuMotion robot base frame.

isaac_sim_to_cumotion_pose(
position_world_to_target: wp.array | np.ndarray | list[float],
orientation_world_to_target: wp.array | np.ndarray | list[float],
position_world_to_base: wp.array | np.ndarray | list[float] | None = None,
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) cumotion.Pose3#

Convert Isaac Sim pose to cuMotion pose in the robot base frame.

Transforms a pose from Isaac Sim world frame to cuMotion’s robot base frame. If base frame transform is not provided, returns the pose in world frame.

Parameters:
  • position_world_to_target – Target position in world frame [x, y, z].

  • orientation_world_to_target – Target orientation in world frame as quaternion [w, x, y, z].

  • position_world_to_base – Robot base position in world frame. Defaults to None (origin).

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

cuMotion Pose3 object representing the target pose in robot base frame.

Example

pose = isaac_sim_to_cumotion_pose(
    position_world_to_target=[1.0, 2.0, 3.0],
    orientation_world_to_target=[1.0, 0.0, 0.0, 0.0],
    position_world_to_base=[0.5, 0.5, 0.0],
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)
isaac_sim_to_cumotion_translation(
position_world_to_target: wp.array | np.ndarray | list[float],
position_world_to_base: wp.array | np.ndarray | list[float] | None = None,
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) np.ndarray#

Convert Isaac Sim position to cuMotion position in robot base frame.

Transforms a position vector from Isaac Sim world frame to cuMotion’s robot base frame.

Parameters:
  • position_world_to_target – Target position in world frame [x, y, z].

  • position_world_to_base – Robot base position in world frame. Defaults to None (origin).

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

Position vector in robot base frame as numpy array of shape (3,).

Raises:

ValueError – If position_world_to_target is not size 3.

Example

position_base = isaac_sim_to_cumotion_translation(
    position_world_to_target=[1.0, 2.0, 3.0],
    position_world_to_base=[0.5, 0.5, 0.0],
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)
isaac_sim_to_cumotion_rotation(
orientation_world_to_target: wp.array | np.ndarray | list[float],
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) cumotion.Rotation3#

Convert Isaac Sim orientation to cuMotion rotation in robot base frame.

Transforms an orientation from Isaac Sim world frame to cuMotion’s robot base frame.

Parameters:
  • orientation_world_to_target – Target orientation in world frame as quaternion [w, x, y, z].

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

cuMotion Rotation3 object representing the orientation in robot base frame.

Raises:

ValueError – If orientation is not size 4.

Example

rotation_base = isaac_sim_to_cumotion_rotation(
    orientation_world_to_target=[1.0, 0.0, 0.0, 0.0],
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)
cumotion_to_isaac_sim_pose(
pose_base_to_target: cumotion.Pose3,
position_world_to_base: wp.array | np.ndarray | list[float] | None = None,
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) tuple[wp.array, wp.array]#

Convert cuMotion pose in base frame to Isaac Sim pose in world frame.

Transforms a pose from cuMotion’s robot base frame to Isaac Sim world frame. If base frame transform is not provided, assumes identity transform.

Parameters:
  • pose_base_to_target – Target pose in robot base frame.

  • position_world_to_base – Robot base position in world frame. Defaults to None (origin).

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

Tuple of (position, quaternion) as warp arrays where position has shape (3,) and quaternion has shape (4,) in (w, x, y, z) format.

Example

position, quaternion = cumotion_to_isaac_sim_pose(
    pose_base_to_target,
    position_world_to_base=[0.5, 0.5, 0.0],
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)
cumotion_to_isaac_sim_translation(
position_base_to_target: np.ndarray,
position_world_to_base: wp.array | np.ndarray | list[float] | None = None,
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) wp.array#

Convert cuMotion position to Isaac Sim position in world frame.

Transforms a position vector from cuMotion’s robot base frame to Isaac Sim world frame.

Parameters:
  • position_base_to_target – Target position in robot base frame [x, y, z].

  • position_world_to_base – Robot base position in world frame. Defaults to None (origin).

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

Position vector in world frame as warp array of shape (3,).

Raises:

ValueError – If position_base_to_target is not size 3.

Example

position_world = cumotion_to_isaac_sim_translation(
    position_base_to_target=np.array([0.5, 1.0, 0.5]),
    position_world_to_base=[0.5, 0.5, 0.0],
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)
cumotion_to_isaac_sim_rotation(
orientation_base_to_target: cumotion.Rotation3,
position_world_to_base: wp.array | np.ndarray | list[float] | None = None,
orientation_world_to_base: wp.array | np.ndarray | list[float] | None = None,
) wp.array#

Convert cuMotion rotation to Isaac Sim orientation in world frame.

Transforms an orientation from cuMotion’s robot base frame to Isaac Sim world frame.

Parameters:
  • orientation_base_to_target – Target orientation in robot base frame.

  • position_world_to_base – Robot base position in world frame (unused, kept for consistency). Defaults to None.

  • orientation_world_to_base – Robot base orientation in world frame as quaternion [w, x, y, z]. Defaults to None (identity).

Returns:

Orientation as warp array quaternion [w, x, y, z] of shape (4,).

Example

quaternion = cumotion_to_isaac_sim_rotation(
    orientation_base_to_target,
    orientation_world_to_base=[1.0, 0.0, 0.0, 0.0]
)