[isaacsim.robot_motion.experimental.motion_generation] motion_generation#

Version: 6.1.1

Contains APIs for interfacing external motion generation code to isaacsim.

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.experimental.motion_generation

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

[dependencies]
"isaacsim.robot_motion.experimental.motion_generation" = {}

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

API#

Python API#

Controllers

BaseController

Interface class for controllers.

ControllerContainer

Controller class which contains any number of controllers.

ParallelController

Controller class which runs multiple controllers in parallel.

SequentialController

Controller class which runs multiple controllers in sequence.

TrajectoryFollower

Controller implementation to follow a generic trajectory.

State Types

RobotState

Composite container for the complete state of a robot.

JointState

Container for the state of robot joints.

RootState

Container for the state of the robot's root link.

SpatialState

Container for the spatial state (pose and twist) of frames.

combine_robot_states

Combine two robot states into a single robot state.

Trajectory and Path

Trajectory

Interface class for defining a continuous-time trajectory for a robot in Isaac Sim.

Path

A path in joint-space represented as a series of waypoints connected linearly.

World Interface

WorldInterface

Abstract interface for planning world implementations.

WorldBinding

Binding that mirrors tracked USD prims into a planning world interface.

Obstacle Handling

ObstacleConfiguration

Define the planning representation and safety tolerance for a shape.

ObstacleRepresentation

Enumerate supported obstacle representations for planning.

ObstacleStrategy

Manage obstacle representation defaults and overrides.

Scene Query

SceneQuery

Interface for searching the USD world for objects with a given TrackableApi.

TrackableApi

Enumerate USD APIs supported by SceneQuery and WorldBinding.


Controllers#

class BaseController#

Bases: ABC

Interface class for controllers.

Controllers implement reset and forward to produce desired robot states based on estimates and optional setpoints.

abstract forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Define the desired state of the robot at the next time-step.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controller.

Returns:

Desired robot state for the robot to track, or None if the controller cannot produce a valid output.

Example:

>>> controller = SomeController()
>>> desired = controller.forward(estimated_state, setpoint_state, t)
>>> if desired is None:
...     print("Controller failed")
abstract reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Reset the internal state of the controller to safe values.

This should be called immediately before running the controller for the first time. This function is intended to bring the controller to a safe initial state.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controller.

Returns:

True if reset succeeded, False otherwise.

Example:

>>> controller = SomeController()
>>> if not controller.reset(estimated_state, setpoint_state, t):
...     raise RuntimeError("Controller reset failed")
class ControllerContainer(
controller_options: dict[Enum, BaseController],
initial_controller_selection: Enum,
)#

Bases: BaseController

Controller class which contains any number of controllers.

Can switch between controllers at run-time using a selection key.

Parameters:
  • controller_options – Mapping of selection keys to controllers.

  • initial_controller_selection – Selection key for the initial controller.

Raises:

ValueError – If no controllers are provided.

Example:

>>> container = ControllerContainer(
...     controller_options=controller_options,
...     initial_controller_selection=initial_selection,
... )
>>> container.get_active_controller_enum() == initial_selection
True
forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Run the active controller.

If the active controller has changed since the last forward call, the controller is switched to the next controller, and then the reset function is called on the new controller.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments.

Returns:

Desired robot state for the robot to track, or None if the active controller fails to produce a valid output.

Raises:

RuntimeError – If resetting the new controller fails during the switch.

Example:

>>> desired = container.forward(estimated_state, setpoint_state, t)
>>> if desired is None:
...     print("Controller failed")
get_active_controller_enum() Enum#

Get the enum of the currently active controller.

This function is typically called by a higher-level behavior control scheme, such as a state-machine or a behavior tree.

Returns:

Selection key for the currently active controller.

Example:

>>> active = container.get_active_controller_enum()
get_controller(
controller_selection: Enum,
) BaseController#

Get a controller object.

This is useful to call custom methods on a controller which are not part of the BaseController interface. For example, many controllers may require long-term goals (setpoints). These types of functions are not part of the BaseController interface, and must be called on the controller object directly.

Parameters:

controller_selection – Selection key for the controller to get.

Returns:

The controller instance.

Raises:

LookupError – If the selected controller is not part of the available options.

Example:

>>> controller = container.get_controller(controller_selection)
reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Set the initial controller to be active again and call reset on it.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments.

Returns:

True if reset succeeded, False otherwise.

Example:

>>> ok = container.reset(estimated_state, setpoint_state, t)
>>> if not ok:
...     raise RuntimeError("Controller reset failed")
set_next_controller(
next_controller_selection: Enum,
)#

Set the controller which will be running starting at the next time-step.

This function is typically called by a higher-level behavior control scheme, such as a state-machine or a behavior tree.

Parameters:

next_controller_selection – Selection key for the controller to switch to.

Raises:

LookupError – If the requested enum does not correspond to any controller.

Example:

>>> container.set_next_controller(next_controller_selection)
class ParallelController(
controllers: list[BaseController],
)#

Bases: BaseController

Controller class which runs multiple controllers in parallel.

This controller runs each controller in parallel, and returns the desired state of the robot as a combination of the desired states of the individual controllers.

Parameters:

controllers – Controllers to run in parallel.

Raises:

ValueError – If fewer than two controllers are provided.

Example:

>>> parallel_controller = ParallelController(controllers)
forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Run all controllers and combine their outputs.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controllers.

Returns:

Combined robot state, or None if any controller fails to produce an output that can be combined (for example, multiple controllers writing to the same part of the state, or a controller failing to produce a valid output).

Example:

>>> desired = parallel_controller.forward(estimated_state, setpoint_state, t)
>>> if desired is None:
...     print("Parallel controller failed")
reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Reset all contained controllers.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controllers.

Returns:

True if all resets succeed, False otherwise.

Example:

>>> ok = parallel_controller.reset(estimated_state, setpoint_state, t)
>>> if not ok:
...     raise RuntimeError("Parallel reset failed")
class SequentialController(
controllers: list[BaseController],
)#

Bases: BaseController

Controller class which runs multiple controllers in sequence.

This controller runs each controller in sequence, giving the desired state of the previous controller as the setpoint to the next controller. The output of the final controller is returned.

Parameters:

controllers – Controllers to run in sequence.

Raises:

ValueError – If fewer than two controllers are provided.

Example:

>>> sequential_controller = SequentialController(controllers)
forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Run controllers sequentially, passing outputs as setpoints.

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

  • setpoint_state – Initial setpoint state for the sequence.

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

  • **kwargs – Additional keyword arguments for the controllers.

Returns:

Robot state produced by the final controller, or None if any controller fails.

Example:

>>> desired = sequential_controller.forward(estimated_state, setpoint_state, t)
>>> if desired is None:
...     print("Sequential controller failed")
reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Reset all contained controllers.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controllers.

Returns:

True if all resets succeed, False otherwise.

Example:

>>> ok = sequential_controller.reset(estimated_state, setpoint_state, t)
>>> if not ok:
...     raise RuntimeError("Sequential reset failed")
class TrajectoryFollower#

Bases: BaseController

Controller implementation to follow a generic trajectory.

The controller requires a trajectory to be set via set_trajectory() before calling reset(). If no trajectory is set, reset() will return False and forward() will return None.

If forward() is called with a time outside of the trajectory bounds, the start time and trajectory are cleared and None is returned.

Initialize a TrajectoryFollower controller.

forward(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) RobotState | None#

Compute the desired robot state from the trajectory at the current time.

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controller.

Returns:

Desired robot state for the current time, or None if no trajectory is set, if reset() has not been called, if the time is outside of the trajectory bounds.

Example:

>>> follower.set_trajectory(trajectory)
>>> follower.reset(estimated_state, setpoint_state, 0.0)
>>> target = follower.forward(estimated_state, setpoint_state, t)
>>> if target is None:
...     print("Controller could not produce a valid result.")
has_trajectory() bool#

Check if the trajectory follower has a trajectory set.

Returns:

True if a trajectory is set, False otherwise.

reset(
estimated_state: RobotState,
setpoint_state: RobotState | None,
t: float,
**kwargs,
) bool#

Set the trajectory start time for the current trajectory.

Sets the start time for the current trajectory to the provided time t. This must be called after set_trajectory() and before the first call to forward().

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

  • setpoint_state – Optional setpoint state of the robot.

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

  • **kwargs – Additional keyword arguments for the controller.

Returns:

True if reset succeeded, False if no trajectory had been set.

set_trajectory(
trajectory: Trajectory,
)#

Set the trajectory to follow.

Sets the trajectory and clears the start time. Call reset() after setting the trajectory to initialize the start time before calling forward().

Parameters:

trajectory – The trajectory to follow.


State Types#

class RobotState(
joints: JointState | None = None,
root: RootState | None = None,
links: SpatialState | None = None,
sites: SpatialState | None = None,
)#

Bases: object

Composite container for the complete state of a robot.

A RobotState aggregates the state of all robot components: joints, root link, rigid bodies, and sites. All components are optional, allowing partial state representations.

Parameters:
  • joints – The state of the robot’s joints.

  • root – The state of the robot’s root link.

  • links – The state of the robot’s non-root rigid bodies.

  • sites – The state of non-link reference frames (tools, sensors, etc.).

Raises:
  • ValueError – If joints is not None and not of type JointState.

  • ValueError – If root is not None and not of type RootState.

  • ValueError – If links is not None and not of type SpatialState.

  • ValueError – If sites is not None and not of type SpatialState.

property joints: JointState | None#

Joint state containing joint positions, velocities, and efforts.

Returns:

The JointState instance containing joint positions, velocities, and efforts, or None if not set.

Link state containing link positions, orientations, and velocities.

Returns:

The SpatialState instance containing link positions, orientations, and velocities, or None if not set.

property root: RootState | None#

Root state containing root position, orientation, and velocities.

Returns:

The RootState instance containing root position, orientation, and velocities, or None if not set.

property sites: SpatialState | None#

Site state containing site positions, orientations, and velocities.

Returns:

The SpatialState instance containing site positions, orientations, and velocities, or None if not set.

class JointState(
robot_joint_space: list[str],
data_array: warp.array,
valid_array: warp.array,
)#

Bases: object

Container for the state of robot joints.

User should almost never call this constructor directly. Instead, use the from_name or from_index methods.

Parameters:
  • robot_joint_space – The ordered list of joint names defining the joint space.

  • data_array – Pre-allocated data array with shape (3, N) where N is the length of robot_joint_space. Row 0 contains positions, row 1 contains velocities, row 2 contains efforts.

  • valid_array – Boolean array with shape (3, N) indicating which fields are valid for each joint.

Raises:
  • ValueError – If data_array is not a 2D wp.array with dtype wp.float32.

  • ValueError – If valid_array is not a 2D wp.array with dtype wp.bool.

  • ValueError – If data_array or valid_array shapes don’t match (3, len(robot_joint_space)).

classmethod from_index(
robot_joint_space: list[str],
positions: tuple[warp.array, warp.array] | None = None,
velocities: tuple[warp.array, warp.array] | None = None,
efforts: tuple[warp.array, warp.array] | None = None,
) JointState#

Create a JointState from joint indices and data arrays.

At least one of positions, velocities, or efforts must be provided. Each tuple contains a 1D warp array of joint indices and a corresponding warp array of values.

Array Shape Support: The data arrays can be either: - 1D arrays (shape: (N,)) where N is the number of joints - 2D arrays (shape: (1, N)) where the first dimension must be size 1

Parameters:
  • robot_joint_space – The ordered list of joint names defining the joint space.

  • positions – Tuple of (indices, position_array) where indices is a 1D warp array of joint indices and position_array is a 1D or 2D warp array (with first dimension size 1) of position values.

  • velocities – Tuple of (indices, velocity_array) where indices is a 1D warp array of joint indices and velocity_array is a 1D or 2D warp array (with first dimension size 1) of velocity values.

  • efforts – Tuple of (indices, effort_array) where indices is a 1D warp array of joint indices and effort_array is a 1D or 2D warp array (with first dimension size 1) of effort values.

Returns:

A JointState instance with the provided joint data.

Raises:
  • ValueError – If all of positions, velocities, and efforts are None.

  • ValueError – If any provided data array is not a 1D or 2D warp array of float types.

  • ValueError – If a 2D array is provided and the first dimension is not size 1.

  • ValueError – If any provided indices array is not a 1D warp array of int types.

  • ValueError – If any provided array has length less than 1.

  • ValueError – If any index is out of range for the robot_joint_space.

  • ValueError – If any index values are duplicated.

  • ValueError – If any array length doesn’t match its corresponding index array length.

Example

# Direct usage with Articulation (no flatten/reshape needed):
robot_joint_space = articulation.dof_names
dof_indices = wp.array([0, 1, 2], dtype=wp.int32)
joint_state = JointState.from_index(
    robot_joint_space=robot_joint_space,
    positions=(dof_indices, articulation.get_dof_positions()),
    velocities=(dof_indices, articulation.get_dof_velocities()),
)

# Or with 1D arrays:
indices = wp.array([0, 1, 2], dtype=wp.int32)
positions_1d = wp.array([0.0, 1.0, 2.0], dtype=wp.float32)
joint_state = JointState.from_index(
    robot_joint_space=["joint_0", "joint_1", "joint_2"],
    positions=(indices, positions_1d),
)
classmethod from_name(
robot_joint_space: list[str],
positions: tuple[list[str], warp.array] | None = None,
velocities: tuple[list[str], warp.array] | None = None,
efforts: tuple[list[str], warp.array] | None = None,
) JointState#

Create a JointState from joint names and data arrays.

At least one of positions, velocities, or efforts must be provided. Each tuple contains a list of joint names and a corresponding warp array of values.

Array Shape Support: The data arrays can be either: - 1D arrays (shape: (N,)) where N is the number of joints - 2D arrays (shape: (1, N)) where the first dimension must be size 1

Parameters:
  • robot_joint_space – The ordered list of joint names defining the joint space of the controlled robot (for example, Articulation.dof_names).

  • positions – Tuple of (joint_names, position_array) where joint_names is a list of joint names and position_array is a 1D or 2D warp array (with first dimension size 1) of position values.

  • velocities – Tuple of (joint_names, velocity_array) where joint_names is a list of joint names and velocity_array is a 1D or 2D warp array (with first dimension size 1) of velocity values.

  • efforts – Tuple of (joint_names, effort_array) where joint_names is a list of joint names and effort_array is a 1D or 2D warp array (with first dimension size 1) of effort values.

Returns:

A JointState instance with the provided joint data.

Raises:
  • ValueError – If all of positions, velocities, and efforts are None.

  • ValueError – If any provided array is not a 1D or 2D warp array of float types.

  • ValueError – If a 2D array is provided and the first dimension is not size 1.

  • ValueError – If any provided array has length less than 1.

  • ValueError – If the first element of any tuple is not a list of joint names.

  • ValueError – If any array length doesn’t match its corresponding name list length.

  • ValueError – If any joint names are duplicated.

  • ValueError – If any joint names are not in the robot_joint_space.

Example

# Direct usage with Articulation (no flatten/reshape needed):
robot_joint_space = articulation.dof_names
joint_state = JointState.from_name(
    robot_joint_space=robot_joint_space,
    positions=(robot_joint_space, articulation.get_dof_positions()),
    velocities=(robot_joint_space, articulation.get_dof_velocities()),
)

# Or with 1D arrays:
positions_1d = wp.array([0.0, 1.0, 2.0], dtype=wp.float32)
joint_state = JointState.from_name(
    robot_joint_space=["joint_0", "joint_1", "joint_2"],
    positions=(["joint_0", "joint_1", "joint_2"], positions_1d),
)
property data_array: warp.array#

Full data array.

Returns:

A 2D warp array with shape (3, N) where N is the length of robot_joint_space. Row 0 contains positions, row 1 contains velocities, row 2 contains efforts.

property effort_indices: warp.array#

List of joint indices that have valid efforts.

Returns:

A 1D warp array containing the indices of joints with valid efforts.

property effort_names: list[str]#

List of joint names that have valid efforts.

Returns:

The list of joint names with valid effort data.

property efforts: wp.array | None#

Valid efforts as a warp array.

Returns:

A 1D warp array containing effort values for joints with valid efforts. Returns None if no efforts are valid.

property position_indices: warp.array#

List of joint indices that have valid positions.

Returns:

A 1D warp array of joint indices with valid position data.

property position_names: list[str]#

List of joint names that have valid positions.

Returns:

The list of joint names with valid position data.

property positions: wp.array | None#

Valid positions as a warp array.

Returns:

A 1D warp array containing position values for joints with valid positions. Returns None if no positions are valid.

property robot_joint_space: list[str]#

List of joints defining the joint-space of this JointState.

Returns:

The ordered list of joint names defining the joint space.

property valid_array: warp.array#

Valid flags array.

Returns:

A 2D boolean warp array with shape (3, N) indicating which fields are valid for each joint. Row 0 corresponds to positions, row 1 to velocities, row 2 to efforts.

property velocities: wp.array | None#

Valid velocities as a warp array.

Returns:

A 1D warp array containing velocity values for joints with valid velocities. Returns None if no velocities are valid.

property velocity_indices: warp.array#

List of joint indices that have valid velocities.

Returns:

A 1D warp array of joint indices with valid velocity data.

property velocity_names: list[str]#

List of joint names that have valid velocities.

Returns:

The list of joint names with valid velocity data.

class RootState(
position: wp.array | None = None,
orientation: wp.array | None = None,
linear_velocity: wp.array | None = None,
angular_velocity: wp.array | None = None,
)#

Bases: object

Container for the state of the robot’s root link.

At least one of position, orientation, linear_velocity, or angular_velocity must be provided. All provided arrays must be 1D warp arrays with the correct number of elements.

All properties are read-only after construction.

Parameters:
  • position – The position of the root as a 1D warp array with 3 elements (x, y, z).

  • orientation – The orientation of the root as a 1D warp array with 4 elements (w, x, y, z).

  • linear_velocity – The linear velocity of the root as a 1D warp array with 3 elements (x, y, z).

  • angular_velocity – The angular velocity of the root as a 1D warp array with 3 elements (x, y, z).

Raises:
  • ValueError – If all of position, orientation, linear_velocity, and angular_velocity are None.

  • ValueError – If any provided array is not a 1D warp array with the correct number of elements.

property angular_velocity: wp.array | None#

Root angular velocity.

Returns:

A 1D warp array with 3 elements (x, y, z) representing the root angular velocity, or None if not set.

property linear_velocity: wp.array | None#

Root linear velocity.

Returns:

A 1D warp array with 3 elements (x, y, z) representing the root linear velocity, or None if not set.

property orientation: wp.array | None#

Root orientation.

Returns:

A 1D warp array with 4 elements (w, x, y, z quaternion) representing the root orientation, or None if not set.

property position: wp.array | None#

Root position.

Returns:

A 1D warp array with 3 elements (x, y, z) representing the root position, or None if not set.

class SpatialState(
spatial_space: list[str],
position_data: warp.array,
linear_velocity_data: warp.array,
orientation_data: warp.array,
angular_velocity_data: warp.array,
valid_array: warp.array,
)#

Bases: object

Container for the spatial state (pose and twist) of frames.

A spatial state represents the pose (position and orientation) and twist (linear and angular velocities) of a set of frames. This can be used for robot links, sites (tool frames), or any other frames of interest.

At least one of positions, orientations, linear_velocities, or angular_velocities must be provided. All provided arrays must be 2D warp arrays with shape (N, K) where N equals the length of names and K is the appropriate dimension for the field.

User should almost never call this constructor directly. Instead, use the from_name or from_index methods.

Parameters:
  • spatial_space – The ordered list of frame names (e.g., link names or site names).

  • position_data – Pre-allocated position data array with shape (N, 3).

  • linear_velocity_data – Pre-allocated linear velocity data array with shape (N, 3).

  • orientation_data – Pre-allocated orientation data array with shape (N, 4).

  • angular_velocity_data – Pre-allocated angular velocity data array with shape (N, 3).

  • valid_array – Boolean array with shape (N, 4) indicating which fields are valid for each frame.

Raises:
  • ValueError – If all of positions, orientations, linear_velocities, and angular_velocities are None.

  • ValueError – If any provided array is not a 2D warp array.

  • ValueError – If any provided array has shape[0] not equal to the length of spatial_space.

  • ValueError – If positions, linear_velocities, or angular_velocities has shape[1] != 3.

  • ValueError – If orientations has shape[1] != 4.

classmethod from_index(
spatial_space: list[str],
positions: tuple[warp.array, warp.array] | None = None,
orientations: tuple[warp.array, warp.array] | None = None,
linear_velocities: tuple[warp.array, warp.array] | None = None,
angular_velocities: tuple[warp.array, warp.array] | None = None,
) SpatialState#

Create a SpatialState from frame indices and data arrays.

At least one of positions, orientations, linear_velocities, or angular_velocities must be provided. Each tuple contains a 1D warp array of frame indices and a corresponding 2D warp array of values.

Parameters:
  • spatial_space – The ordered list of frame names (e.g., link names or site names).

  • positions – Tuple of (indices, position_array) where indices is a 1D warp array of frame indices and position_array is a 2D warp array with shape (N, 3).

  • orientations – Tuple of (indices, orientation_array) where indices is a 1D warp array of frame indices and orientation_array is a 2D warp array with shape (N, 4).

  • linear_velocities – Tuple of (indices, velocity_array) where indices is a 1D warp array of frame indices and velocity_array is a 2D warp array with shape (N, 3).

  • angular_velocities – Tuple of (indices, angular_velocity_array) where indices is a 1D warp array of frame indices and angular_velocity_array is a 2D warp array with shape (N, 3).

Returns:

A SpatialState instance with the provided frame data.

Raises:
  • ValueError – If all of positions, orientations, linear_velocities, and angular_velocities are None.

  • ValueError – If any provided data array is not a 2D warp array of float types.

  • ValueError – If any provided indices array is not a 1D warp array of int types.

  • ValueError – If any provided array has shape[0] less than 1.

  • ValueError – If any index is out of range for the spatial_space.

  • ValueError – If any index values are duplicated.

  • ValueError – If any array shape[0] doesn’t match its corresponding index array length.

  • ValueError – If positions, linear_velocities, or angular_velocities has shape[1] != 3.

  • ValueError – If orientations has shape[1] != 4.

classmethod from_name(
spatial_space: list[str],
positions: tuple[list[str], warp.array] | None = None,
orientations: tuple[list[str], warp.array] | None = None,
linear_velocities: tuple[list[str], warp.array] | None = None,
angular_velocities: tuple[list[str], warp.array] | None = None,
) SpatialState#

Create a SpatialState from frame names and data arrays.

At least one of positions, orientations, linear_velocities, or angular_velocities must be provided. Each tuple contains a list of frame names and a corresponding 2D warp array of values.

Parameters:
  • spatial_space – The ordered list of frame names (e.g., link names or site names).

  • positions – Tuple of (frame_names, position_array) where frame_names is a list of frame names and position_array is a 2D warp array with shape (N, 3).

  • orientations – Tuple of (frame_names, orientation_array) where frame_names is a list of frame names and orientation_array is a 2D warp array with shape (N, 4).

  • linear_velocities – Tuple of (frame_names, velocity_array) where frame_names is a list of frame names and velocity_array is a 2D warp array with shape (N, 3).

  • angular_velocities – Tuple of (frame_names, angular_velocity_array) where frame_names is a list of frame names and angular_velocity_array is a 2D warp array with shape (N, 3).

Returns:

A SpatialState instance with the provided frame data.

Raises:
  • ValueError – If all of positions, orientations, linear_velocities, and angular_velocities are None.

  • ValueError – If any provided array is not a 2D warp array of float types.

  • ValueError – If any provided array has shape[0] less than 1.

  • ValueError – If the first element of any tuple is not a list of frame names.

  • ValueError – If any array shape[0] doesn’t match its corresponding name list length.

  • ValueError – If any frame names are duplicated.

  • ValueError – If any frame names are not in the spatial_space.

  • ValueError – If positions, linear_velocities, or angular_velocities has shape[1] != 3.

  • ValueError – If orientations has shape[1] != 4.

property angular_velocities#

Valid angular velocities as a Warp array.

Returns:

A 2D Warp array with shape (N, 3) containing angular velocity values for frames with valid angular velocities. Returns None if no angular velocities are valid.

property angular_velocity_data#

Full angular velocity data array.

Returns:

A 2D Warp array with shape (N, 3) containing angular velocity data for all frames in the spatial space, regardless of validity flags.

property angular_velocity_indices#

List of frame indices that have valid angular velocities.

Returns:

A 1D Warp array containing the indices of frames with valid angular velocities.

property angular_velocity_names#

List of frame names that have valid angular velocities.

Returns:

A list of frame names that have valid angular velocities.

property linear_velocities#

Valid linear velocities as a Warp array.

Returns:

A 2D Warp array with shape (N, 3) containing linear velocity values for frames with valid linear velocities. Returns None if no linear velocities are valid.

property linear_velocity_data#

Full linear velocity data array.

Returns:

A 2D Warp array with shape (N, 3) containing linear velocity data for all frames in the spatial space, regardless of validity flags.

property linear_velocity_indices#

List of frame indices that have valid linear velocities.

Returns:

A 1D Warp array containing the indices of frames with valid linear velocities.

property linear_velocity_names: list[str]#

List of frame names that have valid linear velocities.

Returns:

The list of frame names that have valid linear velocities.

property orientation_data#

Full orientation data array.

Returns:

A 2D Warp array with shape (N, 4) containing orientation data (quaternions) for all frames in the spatial space, regardless of validity flags.

property orientation_indices: warp.array#

List of frame indices that have valid orientations.

Returns:

A 1D warp array of frame indices that have valid orientations.

property orientation_names: list[str]#

List of frame names that have valid orientations.

Returns:

The list of frame names that have valid orientations.

property orientations: wp.array | None#

Valid orientations as a warp array.

Returns:

A 2D warp array with shape (N, 4) containing orientation values (quaternions) for frames with valid orientations. Returns None if no orientations are valid.

property position_data#

Full position data array.

Returns:

A 2D Warp array with shape (N, 3) containing position data for all frames in the spatial space, regardless of validity flags.

property position_indices: warp.array#

List of frame indices that have valid positions.

Returns:

A 1D warp array of frame indices that have valid positions.

property position_names: list[str]#

List of frame names that have valid positions.

Returns:

The list of frame names that have valid positions.

property positions: wp.array | None#

Valid positions as a warp array.

Returns:

A 2D warp array with shape (N, 3) containing position values for frames with valid positions. Returns None if no positions are valid.

property spatial_space: list[str]#

List of frame names.

Returns:

The ordered list of frame names defining the spatial space.

property valid_array#

Valid flags array.

Returns:

A 2D boolean Warp array with shape (N, 4) indicating which fields are valid for each frame. Column 0 corresponds to positions, column 1 to orientations, column 2 to linear velocities, column 3 to angular velocities.

combine_robot_states(
robot_state_1: RobotState | None,
robot_state_2: RobotState | None,
) RobotState | None#

Combine two robot states into a single robot state.

This function merges two RobotState objects by combining their respective joint states, root states, link states (spatial states), and site states (spatial states). The combination succeeds only if the component states are compatible (i.e., they don’t define conflicting values for the same joints, frames, or root fields).

Parameters:
  • robot_state_1 – The first robot state to combine, or None.

  • robot_state_2 – The second robot state to combine, or None.

Returns:

The combined RobotState if successful, or None if either input is None or if the states cannot be combined due to conflicts.

Example

import warp as wp
from isaacsim.robot_motion.experimental.motion_generation import (
    JointState, RobotState, combine_robot_states
)

# Create two robot states with different joints
state_1 = RobotState(
    joints=JointState.from_name(
        robot_joint_space=["joint_0", "joint_1"],
        positions=(["joint_0"], wp.array([0.0]))
    )
)
state_2 = RobotState(
    joints=JointState.from_name(
        robot_joint_space=["joint_0", "joint_1"],
        positions=(["joint_1"], wp.array([1.0]))
    )
)

# Combine them into a single state
combined = combine_robot_states(state_1, state_2)
# combined.joints.position_names == ["joint_0", "joint_1"]

Trajectory and Path#

class Trajectory#

Bases: ABC

Interface class for defining a continuous-time trajectory for a robot in Isaac Sim.

All trajectories start at time input == 0.0, and end after their duration.

abstract get_target_state(
time: float,
) RobotState | None#

Return the target robot state at the given time.

The Trajectory interface assumes trajectories to be represented continuously between a start time and end time. An instance of this class that internally generates discrete time trajectories will need to implement interpolation for times that have not been computed.

Parameters:

time – Time along the trajectory at which to return the target state.

Returns:

Desired robot state at the given time, or None if the trajectory cannot provide a target.

Example:

>>> target = trajectory.get_target_state(0.5)
>>> if target is None:
...     raise RuntimeError("No target available")
abstract property duration: float#

Return the duration of the trajectory.

Returns:

Duration of the trajectory in seconds.

class Path(waypoints: list | ndarray | warp.array)#

Bases: object

A path in joint-space represented as a series of waypoints connected linearly.

Basic conversion to a trajectory is provided.

Parameters:

waypoints – The waypoints of the path in joint-space. Can be a list, numpy array, or warp array.

Raises:

ValueError – If waypoints is not a two-dimensional array.

get_waypoint_by_index(index: int) ndarray#

Get the waypoint at the given index.

Note this returns a numpy array, not a warp array, as warp arrays are not indexable outside of warp functions/kernels.

Parameters:

index – The index of the waypoint.

Returns:

The waypoint at the given index as a numpy array.

Raises:

IndexError – If the waypoint index is out of range.

get_waypoints() warp.array#

Get the waypoints of the path.

Returns:

The waypoints of the path in joint-space as a warp array.

get_waypoints_count() int#

Get the number of waypoints in the path.

Returns:

The number of waypoints in the path.

to_minimal_time_joint_trajectory(
max_velocities: list | ndarray | warp.array,
max_accelerations: list | ndarray | warp.array,
robot_joint_space: list[str],
active_joints: list[str],
waypoint_relative_difference_tolerance: float = 1e-06,
waypoint_absolute_difference_tolerance: float = 1e-10,
) Trajectory#

Convert the path to a minimal-time trajectory.

Parameters:
  • max_velocities – The maximum joint velocities.

  • max_accelerations – The maximum joint accelerations.

  • robot_joint_space – The ordered list of joint names defining the joint space.

  • active_joints – The active joints.

  • waypoint_relative_difference_tolerance – Minimal relative difference required between waypoints.

  • waypoint_absolute_difference_tolerance – Minimal absolute difference required between waypoints.

Returns:

The minimal-time trajectory.

Raises:
  • ValueError – If waypoints is not a two-dimensional array.

  • ValueError – If max_velocities or max_accelerations is not a one-dimensional array.

  • ValueError – If max_velocities length does not match the joint-dimensionality of waypoints.

  • ValueError – If max_accelerations length does not match the joint-dimensionality of waypoints.

  • ValueError – If active_joints length does not match the joint-dimensionality of waypoints.

  • ValueError – If any max_velocities value is not strictly greater than 0.

  • ValueError – If any max_accelerations value is not strictly greater than 0.

  • ValueError – If tolerance values are less than or equal to 0.

  • ValueError – If consecutive waypoints are equal within the allowed tolerances.

  • ValueError – If there are not at least two waypoints.


World Interface#

class WorldInterface#

Bases: object

Abstract interface for planning world implementations.

This class defines the contract that planning world implementations must fulfill to work with WorldBinding. Subclasses should override all methods to provide actual collision world functionality.

Methods are organized into three categories: - Add methods: Initialize obstacle representations in the planning world. - Update transform methods: Update poses, enables, and scales for existing obstacles. - Update property methods: Update shape-specific properties like radii, sizes, etc.

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.

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 collision enabled state for existing obstacles.

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

  • enabled_array – New collision enabled states.

Raises:

NotImplementedError – If not overridden by subclass.

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 world transforms for existing obstacles.

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

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

Raises:

NotImplementedError – If not overridden by subclass.

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.

class WorldBinding(
world_interface: TWorldInterface,
obstacle_strategy: ObstacleStrategy,
tracked_prims: list[str],
tracked_collision_api: TrackableApi,
)#

Bases: Generic[TWorldInterface]

Binding that mirrors tracked USD prims into a planning world interface.

This class observes specified USD prims on the stage and synchronizes their transforms, collision states, and shape properties to a planning world implementation. It uses USDRT change tracking for efficient updates.

Parameters:
  • world_interface – World implementation to populate and update.

  • obstacle_strategy – Strategy used to select obstacle representations per prim.

  • tracked_prims – Prim paths to track in the USD stage.

  • tracked_collision_api – Collision API which is tracked for enable/disable signal.

Raises:

ValueError – If tracked_collision_api is not a supported collision API.

Example:

from isaacsim.robot_motion.experimental.motion_generation import (
    ObstacleStrategy,
    TrackableApi,
    WorldBinding,
)
from isaacsim.robot_motion.experimental.motion_generation.tests.mirror_world_interface import (
    MirrorWorldInterface, # your planning world interface goes here!
)

world_binding = WorldBinding(
    world_interface=MirrorWorldInterface(),
    obstacle_strategy=ObstacleStrategy(),
    tracked_prims=["/World/Sphere"],
    tracked_collision_api=TrackableApi.PHYSICS_COLLISION,
)
get_world_interface() WorldInterface#

Return the planning world interface instance.

Returns:

The world interface used by this binding.

Example:

from isaacsim.robot_motion.experimental.motion_generation import (
    ObstacleStrategy,
    TrackableApi,
    WorldBinding,
)
from isaacsim.robot_motion.experimental.motion_generation.tests.mirror_world_interface import (
    MirrorWorldInterface,
)

world_binding = WorldBinding(
    world_interface=MirrorWorldInterface(),
    obstacle_strategy=ObstacleStrategy(),
    tracked_prims=[],
    tracked_collision_api=TrackableApi.PHYSICS_COLLISION,
)
world_interface = world_binding.get_world_interface()
initialize()#

Initialize tracking and populate the planning world from tracked prims.

Raises:
  • RuntimeError – If already initialized.

  • RuntimeError – If any tracked prim lacks the CollisionAPI.

  • RuntimeError – If any tracked prim path is invalid in the stage.

  • AssertionError – If any ancestor prims of the tracked prims have non-unity scaling, which would cause issues with world-space operations.

Example:

from isaacsim.robot_motion.experimental.motion_generation import (
    ObstacleStrategy,
    TrackableApi,
    WorldBinding,
)
from isaacsim.robot_motion.experimental.motion_generation.tests.mirror_world_interface import (
    MirrorWorldInterface,
)

world_binding = WorldBinding(
    world_interface=MirrorWorldInterface(),
    obstacle_strategy=ObstacleStrategy(),
    tracked_prims=["/World/Sphere"],
    tracked_collision_api=TrackableApi.PHYSICS_COLLISION,
)
world_binding.initialize()
synchronize()#

Synchronize both transforms and properties of tracked prims into the planning world.

This is a convenience method that calls both synchronize_transforms() and synchronize_properties().

Raises:

RuntimeError – If the world binding has not been initialized.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import (
...     ObstacleStrategy,
...     TrackableApi,
...     WorldBinding,
... )
>>> from isaacsim.robot_motion.experimental.motion_generation.tests.mirror_world_interface import (
...     MirrorWorldInterface,
... )

>>> world_binding = WorldBinding(
...     world_interface=MirrorWorldInterface(),
...     obstacle_strategy=ObstacleStrategy(),
...     tracked_prims=[],
...     tracked_collision_api=TrackableApi.PHYSICS_COLLISION,
... )
>>> world_binding.initialize()
>>> world_binding.synchronize()
synchronize_properties()#

Synchronize tracked prim property changes into the planning world.

Uses USDRT change tracking to efficiently detect and update only the properties that have changed (collision enables, shape-specific attributes). If no changes are detected, this method returns early without performing updates. NOTE: this function does not currently support updating local scales.

Raises:

RuntimeError – If the world binding has not been initialized.

Example:

>>> world_binding.synchronize_properties()
synchronize_transforms()#

Synchronize tracked prim transforms into the planning world.

Updates only the world poses of tracked obstacles without checking for property changes. This is more efficient than synchronize_properties() when only transforms have changed.

Raises:

RuntimeError – If the world binding has not been initialized.

Example:

>>> world_binding.synchronize_transforms()

Obstacle Handling#

class ObstacleConfiguration(
representation: ObstacleRepresentation | str,
safety_tolerance: float,
)#

Bases: object

Define the planning representation and safety tolerance for a shape.

Parameters:
  • representation – Representation type used in planning.

  • safety_tolerance – Safety distance buffer applied to the obstacle.

Raises:

ValueError – if representation is a str that does not map to an ObstacleRepresentation.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import (
...     ObstacleConfiguration,
...     ObstacleRepresentation,
... )
>>>
>>> # Can use string representation
>>> config = ObstacleConfiguration(representation="sphere", safety_tolerance=0.1)
>>> config.representation is ObstacleRepresentation.SPHERE
True
>>> config.safety_tolerance == 0.1
True
>>>
>>> # Or use enum directly
>>> config2 = ObstacleConfiguration(
...     representation=ObstacleRepresentation.SPHERE,
...     safety_tolerance=0.1,
... )
>>> config2.representation is ObstacleRepresentation.SPHERE
True
class ObstacleRepresentation(
value,
names=<not given>,
*values,
module=None,
qualname=None,
type=None,
start=1,
boundary=None,
)#

Bases: StrEnum

Enumerate supported obstacle representations for planning.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import ObstacleRepresentation
>>>
>>> ObstacleRepresentation.SPHERE.name
'SPHERE'
capitalize()#

Return a capitalized version of the string.

More specifically, make the first character have upper case and the rest lower case.

casefold()#

Return a version of the string suitable for caseless comparisons.

center(width, fillchar=' ', /)#

Return a centered string of length width.

Padding is done using the specified fill character (default is a space).

count(sub[, start[, end]]) int#

Return the number of non-overlapping occurrences of substring sub in string S[start:end]. Optional arguments start and end are interpreted as in slice notation.

encode(encoding='utf-8', errors='strict')#

Encode the string using the codec registered for encoding.

encoding

The encoding in which to encode the string.

errors

The error handling scheme to use for encoding errors. The default is ‘strict’ meaning that encoding errors raise a UnicodeEncodeError. Other possible values are ‘ignore’, ‘replace’ and ‘xmlcharrefreplace’ as well as any other name registered with codecs.register_error that can handle UnicodeEncodeErrors.

endswith(suffix[, start[, end]]) bool#

Return True if S ends with the specified suffix, False otherwise. With optional start, test S beginning at that position. With optional end, stop comparing S at that position. suffix can also be a tuple of strings to try.

expandtabs(tabsize=8)#

Return a copy where all tab characters are expanded using spaces.

If tabsize is not given, a tab size of 8 characters is assumed.

find(sub[, start[, end]]) int#

Return the lowest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Return -1 on failure.

format(*args, **kwargs) str#

Return a formatted version of S, using substitutions from args and kwargs. The substitutions are identified by braces (‘{’ and ‘}’).

format_map(mapping) str#

Return a formatted version of S, using substitutions from mapping. The substitutions are identified by braces (‘{’ and ‘}’).

index(sub[, start[, end]]) int#

Return the lowest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Raises ValueError when the substring is not found.

isalnum()#

Return True if the string is an alpha-numeric string, False otherwise.

A string is alpha-numeric if all characters in the string are alpha-numeric and there is at least one character in the string.

isalpha()#

Return True if the string is an alphabetic string, False otherwise.

A string is alphabetic if all characters in the string are alphabetic and there is at least one character in the string.

isascii()#

Return True if all characters in the string are ASCII, False otherwise.

ASCII characters have code points in the range U+0000-U+007F. Empty string is ASCII too.

isdecimal()#

Return True if the string is a decimal string, False otherwise.

A string is a decimal string if all characters in the string are decimal and there is at least one character in the string.

isdigit()#

Return True if the string is a digit string, False otherwise.

A string is a digit string if all characters in the string are digits and there is at least one character in the string.

isidentifier()#

Return True if the string is a valid Python identifier, False otherwise.

Call keyword.iskeyword(s) to test whether string s is a reserved identifier, such as “def” or “class”.

islower()#

Return True if the string is a lowercase string, False otherwise.

A string is lowercase if all cased characters in the string are lowercase and there is at least one cased character in the string.

isnumeric()#

Return True if the string is a numeric string, False otherwise.

A string is numeric if all characters in the string are numeric and there is at least one character in the string.

isprintable()#

Return True if all characters in the string are printable, False otherwise.

A character is printable if repr() may use it in its output.

isspace()#

Return True if the string is a whitespace string, False otherwise.

A string is whitespace if all characters in the string are whitespace and there is at least one character in the string.

istitle()#

Return True if the string is a title-cased string, False otherwise.

In a title-cased string, upper- and title-case characters may only follow uncased characters and lowercase characters only cased ones.

isupper()#

Return True if the string is an uppercase string, False otherwise.

A string is uppercase if all cased characters in the string are uppercase and there is at least one cased character in the string.

join(iterable, /)#

Concatenate any number of strings.

The string whose method is called is inserted in between each given string. The result is returned as a new string.

Example: ‘.’.join([‘ab’, ‘pq’, ‘rs’]) -> ‘ab.pq.rs’

ljust(width, fillchar=' ', /)#

Return a left-justified string of length width.

Padding is done using the specified fill character (default is a space).

lower()#

Return a copy of the string converted to lowercase.

lstrip(chars=None, /)#

Return a copy of the string with leading whitespace removed.

If chars is given and not None, remove characters in chars instead.

static maketrans()#

Return a translation table usable for str.translate().

If there is only one argument, it must be a dictionary mapping Unicode ordinals (integers) or characters to Unicode ordinals, strings or None. Character keys will be then converted to ordinals. If there are two arguments, they must be strings of equal length, and in the resulting dictionary, each character in x will be mapped to the character at the same position in y. If there is a third argument, it must be a string, whose characters will be mapped to None in the result.

partition(sep, /)#

Partition the string into three parts using the given separator.

This will search for the separator in the string. If the separator is found, returns a 3-tuple containing the part before the separator, the separator itself, and the part after it.

If the separator is not found, returns a 3-tuple containing the original string and two empty strings.

removeprefix(prefix, /)#

Return a str with the given prefix string removed if present.

If the string starts with the prefix string, return string[len(prefix):]. Otherwise, return a copy of the original string.

removesuffix(suffix, /)#

Return a str with the given suffix string removed if present.

If the string ends with the suffix string and that suffix is not empty, return string[:-len(suffix)]. Otherwise, return a copy of the original string.

replace(old, new, count=-1, /)#

Return a copy with all occurrences of substring old replaced by new.

count

Maximum number of occurrences to replace. -1 (the default value) means replace all occurrences.

If the optional argument count is given, only the first count occurrences are replaced.

rfind(sub[, start[, end]]) int#

Return the highest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Return -1 on failure.

rindex(sub[, start[, end]]) int#

Return the highest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Raises ValueError when the substring is not found.

rjust(width, fillchar=' ', /)#

Return a right-justified string of length width.

Padding is done using the specified fill character (default is a space).

rpartition(sep, /)#

Partition the string into three parts using the given separator.

This will search for the separator in the string, starting at the end. If the separator is found, returns a 3-tuple containing the part before the separator, the separator itself, and the part after it.

If the separator is not found, returns a 3-tuple containing two empty strings and the original string.

rsplit(sep=None, maxsplit=-1)#

Return a list of the substrings in the string, using sep as the separator string.

sep

The separator used to split the string.

When set to None (the default value), will split on any whitespace character (including n r t f and spaces) and will discard empty strings from the result.

maxsplit

Maximum number of splits. -1 (the default value) means no limit.

Splitting starts at the end of the string and works to the front.

rstrip(chars=None, /)#

Return a copy of the string with trailing whitespace removed.

If chars is given and not None, remove characters in chars instead.

split(sep=None, maxsplit=-1)#

Return a list of the substrings in the string, using sep as the separator string.

sep

The separator used to split the string.

When set to None (the default value), will split on any whitespace character (including n r t f and spaces) and will discard empty strings from the result.

maxsplit

Maximum number of splits. -1 (the default value) means no limit.

Splitting starts at the front of the string and works to the end.

Note, str.split() is mainly useful for data that has been intentionally delimited. With natural text that includes punctuation, consider using the regular expression module.

splitlines(keepends=False)#

Return a list of the lines in the string, breaking at line boundaries.

Line breaks are not included in the resulting list unless keepends is given and true.

startswith(prefix[, start[, end]]) bool#

Return True if S starts with the specified prefix, False otherwise. With optional start, test S beginning at that position. With optional end, stop comparing S at that position. prefix can also be a tuple of strings to try.

strip(chars=None, /)#

Return a copy of the string with leading and trailing whitespace removed.

If chars is given and not None, remove characters in chars instead.

swapcase()#

Convert uppercase characters to lowercase and lowercase characters to uppercase.

title()#

Return a version of the string where each word is titlecased.

More specifically, words start with uppercased characters and all remaining cased characters have lower case.

translate(table, /)#

Replace each character in the string using the given translation table.

table

Translation table, which must be a mapping of Unicode ordinals to Unicode ordinals, strings, or None.

The table must implement lookup/indexing via __getitem__, for instance a dictionary or list. If this operation raises LookupError, the character is left untouched. Characters mapped to None are deleted.

upper()#

Return a copy of the string converted to uppercase.

zfill(width, /)#

Pad a numeric string with zeros on the left, to fill a field of the given width.

The string is never truncated.

CAPSULE = 'capsule'#

Capsular obstacle representation for planning.

CONE = 'cone'#

Conical obstacle representation for planning.

CUBE = 'cube'#

Cubic obstacle representation for planning.

CYLINDER = 'cylinder'#

Cylindrical obstacle representation for planning.

MESH = 'mesh'#

Mesh obstacle representation for planning.

OBB = 'obb'#

Oriented bounding box obstacle representation for planning.

PLANE = 'plane'#

Planar obstacle representation for planning.

SPHERE = 'sphere'#

Spherical obstacle representation for planning.

TRIANGULATED_MESH = 'triangulated_mesh'#

Triangulated mesh obstacle representation for planning.

class ObstacleStrategy#

Bases: object

Manage obstacle representation defaults and overrides.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import ObstacleStrategy
>>> strategy = ObstacleStrategy()
get_obstacle_configuration(
prim_path: str,
) ObstacleConfiguration#

Get the obstacle configuration for a given prim path.

Parameters:

prim_path – Prim path to resolve to a configuration.

Returns:

Obstacle configuration for the prim path.

Raises:

RuntimeError – If the prim path: does not exist on the stage, is unsupported, or configuration is invalid.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import ObstacleStrategy
>>> from isaacsim.core.experimental.objects import Sphere
>>>
>>> strategy = ObstacleStrategy()
>>> _ = Sphere(paths="/World/Sphere")
>>> config = strategy.get_obstacle_configuration("/World/Sphere")
>>> config.safety_tolerance
0.0
set_configuration_overrides(
configurations: dict[str, ObstacleConfiguration],
allow_negative_tolerance: bool = False,
)#

Set the configuration overrides for a given set of prim paths.

Parameters:
  • configurations – Mapping of prim path to override configuration.

  • allow_negative_tolerance – An override flag to allow negative safety tolerances.

Raises:
  • RuntimeError – If any prim paths do not correspond to valid prims on the stage.

  • ValueError – If any representation is invalid for its shape type.

  • ValueError – If any safety tolerance is negative and allow_negative_tolerance is False.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import (
...     ObstacleConfiguration,
...     ObstacleRepresentation,
...     ObstacleStrategy,
... )
>>> from isaacsim.core.experimental.objects import Sphere
>>>
>>> strategy = ObstacleStrategy()
>>> _ = Sphere(paths="/World/Sphere")
>>> strategy.set_configuration_overrides(
...     {
...         "/World/Sphere": ObstacleConfiguration(
...             representation=ObstacleRepresentation.OBB,
...             safety_tolerance=0.1,
...         )
...     }
... )
set_default_configuration(
prim_type: Type[Shape],
configuration: ObstacleConfiguration,
allow_negative_tolerance: bool = False,
)#

Set the default configuration for a given prim type.

Parameters:
  • prim_type – The type of shape for which we want to update the default obstacle configuration.

  • configuration – Configuration to store for the shape type.

  • allow_negative_tolerance – An override flag to allow negative safety tolerances.

Raises:
  • ValueError – If the representation is invalid for the shape type.

  • ValueError – If safety tolerance is negative and allow_negative_tolerance is False.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import (
...     ObstacleConfiguration,
...     ObstacleRepresentation,
...     ObstacleStrategy,
... )
>>> from isaacsim.core.experimental.objects import Sphere
>>>
>>> strategy = ObstacleStrategy()
>>> strategy.set_default_configuration(
...     Sphere,
...     ObstacleConfiguration(
...         representation=ObstacleRepresentation.OBB,
...         safety_tolerance=0.05,
...     ),
... )
set_default_safety_tolerance(
safety_tolerance: float,
allow_negative_tolerance: bool = False,
)#

Set the safety tolerance on the default configuration for all prim types.

Parameters:
  • safety_tolerance – Safety tolerance to apply to all defaults.

  • allow_negative_tolerance – An override flag to allow negative safety tolerances.

Raises:

ValueError – If safety tolerance is negative and allow_negative_tolerance is False.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import ObstacleStrategy
>>>
>>> strategy = ObstacleStrategy()
>>> strategy.set_default_safety_tolerance(0.2)

Scene Query#

class SceneQuery#

Bases: object

Interface for searching the USD world for objects with a given TrackableApi.

Initialize the scene query cache and stage handles.

get_prims_in_aabb(
search_box_origin: wp.array | list[float] | np.ndarray,
search_box_minimum: wp.array | list[float] | np.ndarray,
search_box_maximum: wp.array | list[float] | np.ndarray,
tracked_api: TrackableApi,
include_prim_paths: list[str] | str | None = None,
exclude_prim_paths: list[str] | str | None = None,
) list[str]#

Return prim paths that intersect an AABB and match an applied API filter.

Parameters:
  • search_box_origin – Origin for the AABB bounds.

  • search_box_minimum – Minimum for the AABB bounds, relative to the search_box_origin.

  • search_box_maximum – Maximum bounds in the box frame, relative to the search_box_origin.

  • tracked_api – API schema filter to apply when searching.

  • include_prim_paths – Optional list of prim paths to include (including their children). If this is None, then all prims are included.

  • exclude_prim_paths – Optional list of prim paths to exclude (including their children). If this is None, then no prims are excluded.

Returns:

List of prim paths that intersect the AABB and match the API filter.

Raises:
  • ValueError – If the tracked_api is unsupported.

  • ValueError – If any search bounds are not size 3.

  • ValueError – If minimum bounds are not strictly less than maximum bounds.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import SceneQuery, TrackableApi
>>>
>>> query = SceneQuery()
>>> hits = query.get_prims_in_aabb(
...     search_box_origin=[0.0, 0.0, 0.0],
...     search_box_minimum=[-1.0, -1.0, -1.0],
...     search_box_maximum=[1.0, 1.0, 1.0],
...     tracked_api=TrackableApi.PHYSICS_COLLISION,
... )
get_robots_in_stage() list[str]#

Return robot prim paths in the current stage.

Returns:

List of robot prim paths on the current stage.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import SceneQuery
>>>
>>> query = SceneQuery()
>>> robots = query.get_robots_in_stage()
class TrackableApi(
value,
names=<not given>,
*values,
module=None,
qualname=None,
type=None,
start=1,
boundary=None,
)#

Bases: StrEnum

Enumerate USD APIs supported by SceneQuery and WorldBinding.

Example:

>>> from isaacsim.robot_motion.experimental.motion_generation import TrackableApi
>>>
>>> TrackableApi.PHYSICS_COLLISION.value
'PhysicsCollisionAPI'
capitalize()#

Return a capitalized version of the string.

More specifically, make the first character have upper case and the rest lower case.

casefold()#

Return a version of the string suitable for caseless comparisons.

center(width, fillchar=' ', /)#

Return a centered string of length width.

Padding is done using the specified fill character (default is a space).

count(sub[, start[, end]]) int#

Return the number of non-overlapping occurrences of substring sub in string S[start:end]. Optional arguments start and end are interpreted as in slice notation.

encode(encoding='utf-8', errors='strict')#

Encode the string using the codec registered for encoding.

encoding

The encoding in which to encode the string.

errors

The error handling scheme to use for encoding errors. The default is ‘strict’ meaning that encoding errors raise a UnicodeEncodeError. Other possible values are ‘ignore’, ‘replace’ and ‘xmlcharrefreplace’ as well as any other name registered with codecs.register_error that can handle UnicodeEncodeErrors.

endswith(suffix[, start[, end]]) bool#

Return True if S ends with the specified suffix, False otherwise. With optional start, test S beginning at that position. With optional end, stop comparing S at that position. suffix can also be a tuple of strings to try.

expandtabs(tabsize=8)#

Return a copy where all tab characters are expanded using spaces.

If tabsize is not given, a tab size of 8 characters is assumed.

find(sub[, start[, end]]) int#

Return the lowest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Return -1 on failure.

format(*args, **kwargs) str#

Return a formatted version of S, using substitutions from args and kwargs. The substitutions are identified by braces (‘{’ and ‘}’).

format_map(mapping) str#

Return a formatted version of S, using substitutions from mapping. The substitutions are identified by braces (‘{’ and ‘}’).

index(sub[, start[, end]]) int#

Return the lowest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Raises ValueError when the substring is not found.

isalnum()#

Return True if the string is an alpha-numeric string, False otherwise.

A string is alpha-numeric if all characters in the string are alpha-numeric and there is at least one character in the string.

isalpha()#

Return True if the string is an alphabetic string, False otherwise.

A string is alphabetic if all characters in the string are alphabetic and there is at least one character in the string.

isascii()#

Return True if all characters in the string are ASCII, False otherwise.

ASCII characters have code points in the range U+0000-U+007F. Empty string is ASCII too.

isdecimal()#

Return True if the string is a decimal string, False otherwise.

A string is a decimal string if all characters in the string are decimal and there is at least one character in the string.

isdigit()#

Return True if the string is a digit string, False otherwise.

A string is a digit string if all characters in the string are digits and there is at least one character in the string.

isidentifier()#

Return True if the string is a valid Python identifier, False otherwise.

Call keyword.iskeyword(s) to test whether string s is a reserved identifier, such as “def” or “class”.

islower()#

Return True if the string is a lowercase string, False otherwise.

A string is lowercase if all cased characters in the string are lowercase and there is at least one cased character in the string.

isnumeric()#

Return True if the string is a numeric string, False otherwise.

A string is numeric if all characters in the string are numeric and there is at least one character in the string.

isprintable()#

Return True if all characters in the string are printable, False otherwise.

A character is printable if repr() may use it in its output.

isspace()#

Return True if the string is a whitespace string, False otherwise.

A string is whitespace if all characters in the string are whitespace and there is at least one character in the string.

istitle()#

Return True if the string is a title-cased string, False otherwise.

In a title-cased string, upper- and title-case characters may only follow uncased characters and lowercase characters only cased ones.

isupper()#

Return True if the string is an uppercase string, False otherwise.

A string is uppercase if all cased characters in the string are uppercase and there is at least one cased character in the string.

join(iterable, /)#

Concatenate any number of strings.

The string whose method is called is inserted in between each given string. The result is returned as a new string.

Example: ‘.’.join([‘ab’, ‘pq’, ‘rs’]) -> ‘ab.pq.rs’

ljust(width, fillchar=' ', /)#

Return a left-justified string of length width.

Padding is done using the specified fill character (default is a space).

lower()#

Return a copy of the string converted to lowercase.

lstrip(chars=None, /)#

Return a copy of the string with leading whitespace removed.

If chars is given and not None, remove characters in chars instead.

static maketrans()#

Return a translation table usable for str.translate().

If there is only one argument, it must be a dictionary mapping Unicode ordinals (integers) or characters to Unicode ordinals, strings or None. Character keys will be then converted to ordinals. If there are two arguments, they must be strings of equal length, and in the resulting dictionary, each character in x will be mapped to the character at the same position in y. If there is a third argument, it must be a string, whose characters will be mapped to None in the result.

partition(sep, /)#

Partition the string into three parts using the given separator.

This will search for the separator in the string. If the separator is found, returns a 3-tuple containing the part before the separator, the separator itself, and the part after it.

If the separator is not found, returns a 3-tuple containing the original string and two empty strings.

removeprefix(prefix, /)#

Return a str with the given prefix string removed if present.

If the string starts with the prefix string, return string[len(prefix):]. Otherwise, return a copy of the original string.

removesuffix(suffix, /)#

Return a str with the given suffix string removed if present.

If the string ends with the suffix string and that suffix is not empty, return string[:-len(suffix)]. Otherwise, return a copy of the original string.

replace(old, new, count=-1, /)#

Return a copy with all occurrences of substring old replaced by new.

count

Maximum number of occurrences to replace. -1 (the default value) means replace all occurrences.

If the optional argument count is given, only the first count occurrences are replaced.

rfind(sub[, start[, end]]) int#

Return the highest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Return -1 on failure.

rindex(sub[, start[, end]]) int#

Return the highest index in S where substring sub is found, such that sub is contained within S[start:end]. Optional arguments start and end are interpreted as in slice notation.

Raises ValueError when the substring is not found.

rjust(width, fillchar=' ', /)#

Return a right-justified string of length width.

Padding is done using the specified fill character (default is a space).

rpartition(sep, /)#

Partition the string into three parts using the given separator.

This will search for the separator in the string, starting at the end. If the separator is found, returns a 3-tuple containing the part before the separator, the separator itself, and the part after it.

If the separator is not found, returns a 3-tuple containing two empty strings and the original string.

rsplit(sep=None, maxsplit=-1)#

Return a list of the substrings in the string, using sep as the separator string.

sep

The separator used to split the string.

When set to None (the default value), will split on any whitespace character (including n r t f and spaces) and will discard empty strings from the result.

maxsplit

Maximum number of splits. -1 (the default value) means no limit.

Splitting starts at the end of the string and works to the front.

rstrip(chars=None, /)#

Return a copy of the string with trailing whitespace removed.

If chars is given and not None, remove characters in chars instead.

split(sep=None, maxsplit=-1)#

Return a list of the substrings in the string, using sep as the separator string.

sep

The separator used to split the string.

When set to None (the default value), will split on any whitespace character (including n r t f and spaces) and will discard empty strings from the result.

maxsplit

Maximum number of splits. -1 (the default value) means no limit.

Splitting starts at the front of the string and works to the end.

Note, str.split() is mainly useful for data that has been intentionally delimited. With natural text that includes punctuation, consider using the regular expression module.

splitlines(keepends=False)#

Return a list of the lines in the string, breaking at line boundaries.

Line breaks are not included in the resulting list unless keepends is given and true.

startswith(prefix[, start[, end]]) bool#

Return True if S starts with the specified prefix, False otherwise. With optional start, test S beginning at that position. With optional end, stop comparing S at that position. prefix can also be a tuple of strings to try.

strip(chars=None, /)#

Return a copy of the string with leading and trailing whitespace removed.

If chars is given and not None, remove characters in chars instead.

swapcase()#

Convert uppercase characters to lowercase and lowercase characters to uppercase.

title()#

Return a version of the string where each word is titlecased.

More specifically, words start with uppercased characters and all remaining cased characters have lower case.

translate(table, /)#

Replace each character in the string using the given translation table.

table

Translation table, which must be a mapping of Unicode ordinals to Unicode ordinals, strings, or None.

The table must implement lookup/indexing via __getitem__, for instance a dictionary or list. If this operation raises LookupError, the character is left untouched. Characters mapped to None are deleted.

upper()#

Return a copy of the string converted to uppercase.

zfill(width, /)#

Pad a numeric string with zeros on the left, to fill a field of the given width.

The string is never truncated.

MOTION_GENERATION_COLLISION = 'IsaacMotionPlanningAPI'#

IsaacMotionPlanningAPI identifier.

PHYSICS_COLLISION = 'PhysicsCollisionAPI'#

USD PhysicsCollisionAPI identifier.

PHYSICS_RIGID_BODY = 'PhysicsRigidBodyAPI'#

USD PhysicsRigidBodyAPI identifier.