Motion Generation Extension [omni.isaac.motion_generation]

World Interface

class WorldInterface

Interface for translating USD world to a generic world-aware algorithm such as a MotionPolicy

update_world(updated_obstacles: Optional[List] = None)None

Applies all necessary updates to the internal world representation.

Parameters

updated_obstacles (list, optional) – If provided, only the given obstacles will have their poses updated. For motion policies that use obstacle poses relative to the robot base (e.g. Lula based policies), this list will be ignored if the robot base has moved because all object poses will have changed relative to the robot. Defaults to None.

Returns

None

add_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>, static: Optional[bool] = False)bool

Add an obstacle

Parameters
  • obstacle (omni.isaac.core.objects) – An obstacle from the package omni.isaac.core.obstacles The type of the obstacle will be checked, and the appropriate add function will be called

  • static (Optional[bool]) – When True, the obstacle will be assumed to remain stationary relative to the USD global frame over time

Returns

Returns True if the obstacle type is valid and the appropriate add function has been implemented

Return type

success (bool)

add_cuboid(cuboid: Union[omni.isaac.core.objects.cuboid.DynamicCuboid, omni.isaac.core.objects.cuboid.FixedCuboid, omni.isaac.core.objects.cuboid.VisualCuboid], static: bool = False)bool

Add a block obstacle.

Parameters
  • cuboid (core.objects.cuboid) – Wrapper object for handling rectangular prism Usd Prims.

  • static (bool, optional) – If True, indicate that cuboid will never change pose, and may be ignored in internal world updates. Defaults to False.

Returns

Return True if underlying WorldInterface has implemented add_cuboid()

Return type

bool

add_sphere(sphere: Union[omni.isaac.core.objects.sphere.DynamicSphere, omni.isaac.core.objects.sphere.VisualSphere], static: bool = False)bool

Add a sphere obstacle.

Parameters
  • sphere (core.objects.sphere) – Wrapper object for handling sphere Usd Prims.

  • static (bool, optional) – If True, indicate that sphere will never change pose, and may be ignored in internal world updates. Defaults to False.

Returns

Return True if underlying WorldInterface has implemented add_sphere()

Return type

bool

add_capsule(capsule: Union[omni.isaac.core.objects.capsule.DynamicCapsule, omni.isaac.core.objects.capsule.VisualCapsule], static: bool = False)bool

Add a capsule obstacle.

Parameters
  • capsule (core.objects.capsule) – Wrapper object for handling capsule Usd Prims.

  • static (bool, optional) – If True, indicate that capsule will never change pose, and may be ignored in internal world updates. Defaults to False.

Returns

Return True if underlying WorldInterface has implemented add_capsule()

Return type

bool

add_cylinder(cylinder: Union[omni.isaac.core.objects.cylinder.DynamicCylinder, omni.isaac.core.objects.cylinder.VisualCylinder], static: bool = False)bool

Add a cylinder obstacle.

Parameters
  • cylinder (core.objects.cylinder) – Wrapper object for handling rectangular prism Usd Prims.

  • static (bool, optional) – If True, indicate that cuboid will never change pose, and may be ignored in internal world updates. Defaults to False.

Returns

Return True if underlying WorldInterface has implemented add_cylinder()

Return type

bool

add_cone(cone: Union[omni.isaac.core.objects.cone.DynamicCone, omni.isaac.core.objects.cone.VisualCone], static: bool = False)bool

Add a cone obstacle.

Parameters
  • cone (core.objects.cone) – Wrapper object for handling cone Usd Prims.

  • static (bool, optional) – If True, indicate that cone will never change pose, and may be ignored in internal world updates. Defaults to False.

Returns

Return True if underlying WorldInterface has implemented add_cone()

Return type

bool

add_ground_plane(ground_plane: omni.isaac.core.objects.ground_plane.GroundPlane)bool

Add a ground_plane

Parameters

ground_plane (core.objects.ground_plane.GroundPlane) – Wrapper object for handling ground_plane Usd Prims.

Returns

Return True if underlying WorldInterface has implemented add_ground_plane()

Return type

bool

disable_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Disable collision avoidance for obstacle.

Parameters

obstacle (core.object) – obstacle to be disabled.

Returns

Return True if obstacle was identified and successfully disabled.

Return type

bool

enable_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Enable collision avoidance for obstacle.

Parameters

obstacle (core.object) – obstacle to be enabled.

Returns

Return True if obstacle was identified and successfully enabled.

Return type

bool

remove_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Remove obstacle from collision avoidance. Obstacle cannot be re-enabled via enable_obstacle() after removal.

Parameters

obstacle (core.object) – obstacle to be removed.

Returns

Return True if obstacle was identified and successfully removed.

Return type

bool

reset()None

Reset all state inside the WorldInterface to its initial values

Motion Policy Interface

class MotionPolicy

Interface for implementing a MotionPolicy: a collision-aware algorithm for dynamically moving a robot to a target. The MotionPolicy interface inherits from the WorldInterface class. A MotionPolicy can be passed to an ArticulationMotionPolicy to streamline moving the simulated robot.

set_robot_base_pose(robot_translation: numpy.array, robot_orientation: numpy.array)

Update position of the robot base.

Parameters
  • robot_translation (np.array) – (3 x 1) translation vector describing the translation of the robot base relative to the USD stage origin. The translation vector should be specified in the units of the USD stage

  • robot_orientation (np.array) – (4 x 1) quaternion describing the orientation of the robot base relative to the USD stage global frame

compute_joint_targets(active_joint_positions: numpy.array, active_joint_velocities: numpy.array, watched_joint_positions: numpy.array, watched_joint_velocities: numpy.array, frame_duration: float)Tuple[numpy.array, numpy.array]

Compute position and velocity targets for the next frame given the current robot state. Position and velocity targets are used in Isaac Sim to generate forces using the PD equation kp*(joint_position_targets-joint_positions) + kd*(joint_velocity_targets-joint_velocities).

Parameters
  • active_joint_positions (np.array) – current positions of joints specified by get_active_joints()

  • active_joint_velocities (np.array) – current velocities of joints specified by get_active_joints()

  • watched_joint_positions (np.array) – current positions of joints specified by get_watched_joints()

  • watched_joint_velocities (np.array) – current velocities of joints specified by get_watched_joints()

  • frame_duration (float) – duration of the physics frame

Returns

joint position targets for the active robot joints for the next frame

joint velocity targets for the active robot joints for the next frame

Return type

Tuple[np.array,np.array]

get_active_joints()List[str]

Active joints are directly controlled by this MotionPolicy

Some articulated robot joints may be ignored by some policies. E.g., the gripper of the Franka arm is not used to follow targets, and the RMPflow config files excludes the joints in the gripper from the list of articulated joints.

Returns

names of active joints. The order of joints in this list determines the order in which a MotionPolicy expects joint states to be specified in functions like compute_joint_targets(active_joint_positions,…)

Return type

List[str]

get_watched_joints()List[str]

Watched joints are joints whose position/velocity matters to the MotionPolicy, but are not directly controlled. e.g. A MotionPolicy may control a robot arm on a mobile robot. The joint states in the rest of the robot directly affect the position of the arm, but they are not actively controlled by this MotionPolicy

Returns

Names of joints that are being watched by this MotionPolicy. The order of joints in this list determines the order in which a MotionPolicy expects joint states to be specified in functions like compute_joint_targets(…,watched_joint_positions,…)

Return type

List[str]

set_cspace_target(active_joint_targets: numpy.array)None

Set configuration space target for the robot.

Parameters

active_joint_target (np.array) – Desired configuration for the robot as (m x 1) vector where m is the number of active joints.

Returns

None

set_end_effector_target(target_translation=None, target_orientation=None)None

Set end effector target.

Parameters
  • target_translation (nd.array) – Translation vector (3x1) for robot end effector. Target translation should be specified in the same units as the USD stage, relative to the stage origin.

  • target_orientation (nd.array) – Quaternion of desired rotation for robot end effector relative to USD stage global frame

Returns

None

class RmpFlow(robot_description_path: str, urdf_path: str, rmpflow_config_path: str, end_effector_frame_name: str, evaluations_per_frame: int, ignore_robot_state_updates=False)

RMPflow is a real-time, reactive motion policy that smoothly guides a robot to task space targets while avoiding dynamic obstacles. This class implements the MotionPolicy interface, as well as providing a number of RmpFlow-specific functions such as visualizing the believed robot position and changing internal settings.

Parameters
  • robot_description_path (str) – path to a robot description yaml file

  • urdf_path (str) – path to robot urdf

  • rmpflow_config_path (str) – path to an rmpflow parameter yaml file

  • end_effector_frame_name (str) – name of the robot end effector frame (must be present in the robot urdf)

  • ignore_robot_state_updates (bool) – Defaults to False. If False: RmpFlow will set the internal robot state to match the arguments to compute_joint_targets(). When paired with ArticulationMotionPolicy, this means that RMPflow uses the simulated robot’s state at every frame. If True: RmpFlow will roll out the robot state internally after it is initially specified in the first call to compute_joint_targets().

set_ignore_state_updates(ignore_robot_state_updates)None

An RmpFlow specific method; set an internal flag in RmpFlow: ignore_robot_state_updates

Parameters

ignore_robot_state_updates (bool) –

If False:

RmpFlow will set the internal robot state to match the arguments to compute_joint_targets(). When paired with ArticulationMotionPolicy, this means that RMPflow uses the simulated robot’s state at every frame.

If True:

RmpFlow will roll out the robot state internally after it is initially specified in the first call to compute_joint_targets(). The caller may override this flag and directly change the internal robot state with RmpFlow.set_internal_robot_joint_states().

set_cspace_target(active_joint_targets)None

Set a cspace target for RmpFlow. RmpFlow always has a cspace target, and setting a new cspace target does not override a position target. RmpFlow uses the cspace target to help resolve null space behavior when a position target can be acheived in a variety of ways. If the end effector target is explicitly set to None, RmpFlow will move the robot to the cspace target

Parameters

active_joint_targets (np.array) – cspace position target for active joints in the robot

update_world(updated_obstacles: Optional[List] = None)None

Update the internal world state of Lula. This function automatically tracks the positions of obstacles that have been added with add_obstacle()

Parameters

updated_obstacles (List[core.objects], optional) – Obstacles that have been added by add_obstacle() that need to be updated. If not specified, all non-static obstacle positions will be updated. If specified, only the obstacles that have been listed will have their positions updated

compute_joint_targets(active_joint_positions: numpy.array, active_joint_velocities: numpy.array, watched_joint_positions: numpy.array, watched_joint_velocities: numpy.array, frame_duration: float)Tuple[numpy.array, numpy.array]

Compute robot joint targets for the next frame based on the current robot position. RmpFlow will ignore active joint positions and velocities if it has been set to ignore_robot_state_updates RmpFlow does not currently support watching joints that it is not actively controlling.

Parameters
  • active_joint_positions (np.array) – current positions of joints specified by get_active_joints()

  • active_joint_velocities (np.array) – current velocities of joints specified by get_active_joints()

  • watched_joint_positions (np.array) – current positions of joints specified by get_watched_joints() This will always be empty for RmpFlow.

  • watched_joint_velocities (np.array) – current velocities of joints specified by get_watched_joints() This will always be empty for RmpFlow.

  • frame_duration (float) – duration of the physics frame

Returns

active_joint_position_targets : Position targets for the robot in the next frame

active_joint_velocity_targets : Velocity targets for the robot in the next frame

Return type

Tuple[np.array,np.array]

visualize_collision_spheres()None

An RmpFlow specific debugging method. This function creates visible sphere prims that match the locations and radii of the collision spheres that RmpFlow uses to prevent robot collisions. Once created, RmpFlow will update the sphere locations whenever its internal robot state changes. This can be used alongside RmpFlow.ignore_robot_state_updates(True) to validate RmpFlow’s internal representation of the robot as well as help tune the PD gains on the simulated robot; i.e. the simulated robot should match the positions of the RmpFlow collision spheres over time.

Visualizing collision spheres as prims on the stage is likely to significantly slow down the framerate of the simulation. This function should only be used for debugging purposes

visualize_end_effector_position()None

An RmpFlow specific debugging method. This function creates a visible cube whose translation and orientation match where RmpFlow believes the robot end effector to be. Once created, RmpFlow will update the position of the cube whenever its internal robot state changes.

stop_visualizing_collision_spheres()None

An RmpFlow specific debugging method. This function removes the collision sphere prims created by either RmpFlow.visualize_collision_spheres() or RmpFlow.get_collision_spheres_as_prims(). Rather than making the prims invisible, they are deleted from the stage to increase performance

stop_visualizing_end_effector()None

An RmpFlow specific debugging method. This function removes the end effector prim that can be created by visualize_end_effector_position() or get_end_effector_position_as_prim()

get_collision_spheres_as_prims()List

An RmpFlow specific debugging method. This function is similar to RmpFlow.visualize_collision_spheres(). If the collision spheres have already been added to the stage as prims, they will be returned. If the collision spheres have not been added to the stage as prims, they will be created and returned. If created in this function, the spheres will be invisible until RmpFlow.visualize_collision_spheres() is called.

Visualizing collision spheres on the stage is likely to significantly slow down the framerate of the simulation. This function should only be used for debugging purposes

Returns

List of prims representing RmpFlow’s internal collision spheres

Return type

collision_spheres (List[core.objects.sphere.VisualSphere])

get_end_effector_as_prim()omni.isaac.core.objects.cuboid.VisualCuboid

An RmpFlow specific debugging method. This function is similar to RmpFlow.visualize_end_effector_position(). If the end effector has already been visualized as a prim, it will be returned. If the end effector is not being visualized, a cuboid will be created and returned. If created in this function, the end effector will be invisible until RmpFlow.visualize_end_effector_position() is called.

Returns

Cuboid whose translation and orientation match RmpFlow’s believed robot end effector position.

Return type

end_effector_prim (objects.cuboid.VisualCuboid)

delete_collision_sphere_prims()None

An RmpFlow specific debugging method. This function deletes any prims that have been created by RmpFlow to visualize its internal collision spheres

delete_end_effector_prim()None

An RmpFlow specific debugging method. If RmpFlow is maintaining a prim for its believed end effector position, this function will delete the prim.

reset()None

Reset RmpFlow to its initial state

set_internal_robot_joint_states(active_joint_positions: numpy.array, active_joint_velocities: numpy.array, watched_joint_positions: numpy.array, watched_joint_velocities: numpy.array)None

An RmpFlow specific method; this function overwrites the robot state regardless of the ignore_robot_state_updates flag. RmpFlow does not currently support watching joints that it is not actively controlling.

Parameters
  • active_joint_positions (np.array) – current positions of joints specified by get_active_joints()

  • active_joint_velocities (np.array) – current velocities of joints specified by get_active_joints()

  • watched_joint_positions (np.array) – current positions of joints specified by get_watched_joints(). This will always be empty for RmpFlow.

  • watched_joint_velocities (np.array) – current velocities of joints specified by get_watched_joints() This will always be empty for RmpFlow.

get_internal_robot_joint_states()Tuple[numpy.array, numpy.array, numpy.array, numpy.array]

An RmpFlow specific method; this function returns the internal robot state that is believed by RmpFlow

Returns

active_joint_positions: believed positions of active joints

active_joint_velocities: believed velocities of active joints

watched_joint_positions: believed positions of watched robot joints. This will always be empty for RmpFlow.

watched_joint_velocities: believed velocities of watched robot joints. This will always be empty for RmpFlow.

Return type

Tuple[np.array,np.array,np.array,np.array]

get_active_joints()List[str]

Returns a list of joint names that RmpFlow is controlling.

Some articulated robot joints may be ignored by some policies. E.g., the gripper of the Franka arm is not used to follow targets, and the RmpFlow config files excludes the joints in the gripper from the list of active joints.

Returns

Names of active joints.

The order of the joints in this list matches the order that the joints are expected in functions like RmpFlow.compute_joint_targets(active_joint_positions, active_joint_velocities,…)

Return type

active_joints (List[str])

get_watched_joints()List[str]

Currently, RmpFlow is not capable of watching joint states that are not being directly controlled (active joints) If RmpFlow is controlling a robot arm at the end of an externally controlled body, set_robot_base_pose() can be used to make RmpFlow aware of the robot position This means that RmpFlow is not currently able to support controlling a set of DOFs in a robot that are not sequentially linked to each other or are not connected via fixed transforms to the end effector.

Returns

Empty list

Return type

watched_joints (List[str])

get_end_effector_pose(active_joint_positions: numpy.array)Tuple[numpy.array, numpy.array]

Return pose of robot end effector given current joint positions. The end effector position will be transformed into world coordinates based on the believed position of the robot base. See set_robot_base_pose()

Parameters

active_joint_positions (np.array) – positions of the active joints in the robot

Returns

end_effector_translation: (3x1) translation vector for the robot end effector

relative to the USD stage origin

end_effector_rotation: (3x3) rotation matrix describing the orientation of the

robot end effector relative to the USD global frame

Return type

Tuple[np.array,np.array]

get_kinematics_solver()omni.isaac.motion_generation.lula.kinematics.LulaKinematicsSolver

Return a LulaKinematicsSolver that uses the same robot description as RmpFlow. The robot base pose of the LulaKinematicsSolver will be set to the same base pose as RmpFlow, but the two objects must then have their base poses updated separately.

Returns

Kinematics solver using the same cspace as RmpFlow

Return type

LulaKinematicsSolver

set_end_effector_target(target_position=None, target_orientation=None)None

Set end effector target.

Parameters
  • target_translation (nd.array) – Translation vector (3x1) for robot end effector. Target translation should be specified in the same units as the USD stage, relative to the stage origin.

  • target_orientation (nd.array) – Quaternion of desired rotation for robot end effector relative to USD stage global frame

Returns

None

set_robot_base_pose(robot_position: numpy.array, robot_orientation: numpy.array)None

Update position of the robot base. Until this function is called, Lula will assume the base pose to be at the origin with identity rotation.

Parameters
  • robot_position (np.array) – (3 x 1) translation vector describing the translation of the robot base relative to the USD stage origin. The translation vector should be specified in the units of the USD stage

  • robot_orientation (np.array) – (4 x 1) quaternion describing the orientation of the robot base relative to the USD stage global frame

add_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>, static: bool = False)bool

Add an obstacle

Parameters
  • obstacle (omni.isaac.core.objects) – An obstacle from the package omni.isaac.core.obstacles The type of the obstacle will be checked, and the appropriate add function will be called

  • static (Optional[bool]) – When True, the obstacle will be assumed to remain stationary relative to the USD global frame over time

Returns

Returns True if the obstacle type is valid and the appropriate add function has been implemented

Return type

success (bool)

add_cuboid(cuboid: Union[omni.isaac.core.objects.cuboid.DynamicCuboid, omni.isaac.core.objects.cuboid.FixedCuboid, omni.isaac.core.objects.cuboid.VisualCuboid], static: bool = False)bool

Add a block obstacle.

Parameters
  • cuboid (core.objects.cuboid) – Wrapper object for handling rectangular prism Usd Prims.

  • static (bool, optional) – If True, indicate that cuboid will never change pose, and may be ignored in internal world updates. Since Lula specifies object positions relative to the robot’s frame of reference, static obstacles will have their positions queried any time that set_robot_base_pose() is called. Defaults to False.

Returns

Always True, indicating that this adder has been implemented

Return type

bool

add_sphere(sphere: Union[omni.isaac.core.objects.sphere.DynamicSphere, omni.isaac.core.objects.sphere.VisualSphere], static: bool = False)bool

Add a sphere obstacle.

Parameters
  • sphere (core.objects.sphere) – Wrapper object for handling sphere Usd Prims.

  • static (bool, optional) – If True, indicate that sphere will never change pose, and may be ignored in internal world updates. Since Lula specifies object positions relative to the robot’s frame of reference, static obstacles will have their positions queried any time that set_robot_base_pose() is called. Defaults to False.

Returns

Always True, indicating that this adder has been implemented

Return type

bool

add_capsule(capsule: Union[omni.isaac.core.objects.capsule.DynamicCapsule, omni.isaac.core.objects.capsule.VisualCapsule], static: bool = False)bool

Add a capsule obstacle.

Parameters
  • capsule (core.objects.capsule) – Wrapper object for handling capsule Usd Prims.

  • static (bool, optional) – If True, indicate that capsule will never change pose, and may be ignored in internal world updates. Since Lula specifies object positions relative to the robot’s frame of reference, static obstacles will have their positions queried any time that set_robot_base_pose() is called. Defaults to False.

Returns

Always True, indicating that this function has been implemented

Return type

bool

add_ground_plane(ground_plane: omni.isaac.core.objects.ground_plane.GroundPlane)bool

Add a ground_plane. Lula does not support ground planes directly, and instead internally creates a cuboid with an expansive face (dimensions 200x200 stage units) coplanar to the ground_plane.

Parameters
  • ground_plane (core.objects.ground_plane.GroundPlane) – Wrapper object for handling ground_plane Usd Prims.

  • plane_width (Optional[float]) – The width of the ground plane (in meters) that Lula creates to constrain this robot. Defaults to 50.0 m

Returns

Always True, indicating that this adder has been implemented

Return type

bool

disable_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Disable collision avoidance for obstacle.

Parameters

obstacle (core.objects) – obstacle to be disabled.

Returns

Return True if obstacle was identified and successfully disabled.

Return type

bool

enable_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Enable collision avoidance for obstacle.

Parameters

obstacle (core.objects) – obstacle to be enabled.

Returns

Return True if obstacle was identified and successfully enabled.

Return type

bool

remove_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)bool

Remove obstacle from collision avoidance. Obstacle cannot be re-enabled via enable_obstacle() after removal.

Parameters

obstacle (core.objects) – obstacle to be removed.

Returns

Return True if obstacle was identified and successfully removed.

Return type

bool

ArticulationMotionPolicy

class ArticulationMotionPolicy(robot_articulation: omni.isaac.core.articulations.articulation.Articulation, motion_policy: omni.isaac.motion_generation.motion_policy_interface.MotionPolicy, physics_dt: float)

Wrapper class for running MotionPolicy on simulated robots.

Parameters
  • robot_articulation (Articulation) – an initialized robot Articulation object

  • motion_policy (MotionPolicy) – an instance of a class that implements the MotionPolicy interface

  • physics_dt (float) – Duration of a physics step in Isaac Sim (typically 1/60 s).

Returns

None

move()None

Use underlying MotionPolicy to compute and apply joint targets to the robot over the next frame.

Returns

None

get_next_articulation_action()omni.isaac.core.utils.types.ArticulationAction

Use underlying MotionPolicy to compute joint targets for the robot over the next frame.

Returns

Desired position/velocity target for the robot in the next frame

Return type

ArticulationAction

get_active_joints_subset()omni.isaac.motion_generation.articulation_subset.ArticulationSubset

Get view into active joints

Returns

returns robot states for active joints in an order compatible with the MotionPolicy

Return type

ArticulationSubset

get_watched_joints_subset()omni.isaac.motion_generation.articulation_subset.ArticulationSubset

Get view into watched joints

Returns

returns robot states for watched joints in an order compatible with the MotionPolicy

Return type

ArticulationSubset

get_robot_articulation()omni.isaac.core.articulations.articulation.Articulation

Get the underlying Articulation object representing the robot.

Returns

Articulation object representing the robot.

Return type

Articulation

get_motion_policy()omni.isaac.motion_generation.motion_policy_interface.MotionPolicy

Get MotionPolicy that is being used to compute ArticulationActions

Returns

MotionPolicy being used to compute ArticulationActions

Return type

MotionPolicy

KinematicsSolver

class KinematicsSolver

An limitted interface for computing robot kinematics that includes forward and inverse kinematics. This interface ommits more advanced kinematics such as Jacobians, as they are not required for most use-cases.

This interface inherits from the WorldInterface to standardize the inputs to collision-aware IK solvers, but it is not necessary for all implementations to implement the WorldInterface. See KinematicsSolver.supports_collision_avoidance()

set_robot_base_pose(robot_positions: numpy.array, robot_orientation: numpy.array)None

Update position of the robot base. This will be used to compute kinematics relative to the USD stage origin.

Parameters
  • robot_positions (np.array) – (3 x 1) translation vector describing the translation of the robot base relative to the USD stage origin. The translation vector should be specified in the units of the USD stage

  • robot_orientation (np.array) – (4 x 1) quaternion describing the orientation of the robot base relative to the USD stage global frame

get_joint_names()List[str]

Return a list containing the names of all joints in the given kinematic structure. The order of this list determines the order in which the joint positions are expected in compute_forward_kinematics(joint_positions,…) and the order in which they are returned in compute_inverse_kinematics()

Returns

Names of all joints in the robot

Return type

List[str]

get_all_frame_names()List[str]

Return a list of all the frame names in the given kinematic structure

Returns

All frame names in the kinematic structure. Any of which can be used to compute forward or inverse kinematics.

Return type

List[str]

compute_forward_kinematics(frame_name: str, joint_positions: numpy.array, position_only: Optional[bool] = False)Tuple[numpy.array, numpy.array]

Compute the position of a given frame in the robot relative to the USD stage global frame

Parameters
  • frame_name (str) – Name of robot frame on which to calculate forward kinematics

  • joint_positions (np.array) – Joint positions for the joints returned by get_joint_names()

  • position_only (bool) – If True, only the frame positions need to be calculated and the returned rotation may be left undefined.

Returns

frame_positions: (3x1) vector describing the translation of the frame relative to the USD stage origin

frame_rotation: (3x3) rotation matrix describing the rotation of the frame relative to the USD stage global frame

Return type

Tuple[np.array,np.array]

compute_inverse_kinematics(frame_name: str, target_positions: numpy.array, target_orientation: Optional[numpy.array] = None, warm_start: Optional[numpy.array] = None, position_tolerance: Optional[float] = None, orientation_tolerance: Optional[float] = None)Tuple[numpy.array, bool]

Compute joint positions such that the specified robot frame will reach the desired translations and rotations

Parameters
  • frame_name (str) – name of the target frame for inverse kinematics

  • target_position (np.array) – target translation of the target frame (in stage units) relative to the USD stage origin

  • target_orientation (np.array) – target orientation of the target frame relative to the USD stage global frame. Defaults to None.

  • warm_start (np.array) – a starting position that will be used when solving the IK problem. Defaults to None.

  • position_tolerance (float) – l-2 norm of acceptable position error (in stage units) between the target and achieved translations. Defaults to None.

  • tolerance (orientation) – magnitude of rotation (in radians) separating the target orientation from the achieved orienatation. orientation_tolerance is well defined for values between 0 and pi. Defaults to None.

Returns

joint_positions: in the order specified by get_joint_names() which result in the target frame acheiving the desired position

success: True if the solver converged to a solution within the given tolerances

Return type

Tuple[np.array,bool]

supports_collision_avoidance()bool

Returns a bool describing whether the inverse kinematics support collision avoidance. If the policy does not support collision avoidance, none of the obstacle add/remove/enable/disable functions need to be implemented.

Returns

If True, the IK solver will avoid any obstacles that have been added

Return type

bool

class LulaKinematicsSolver(robot_description_path: str, urdf_path: str, robot_description: Optional[lula.RobotDescription] = None)

A Lula-based implementaion of the KinematicsSolver interface. Lula uses a URDF file describing the robot and a custom yaml file that specifies the cspace of the robot and other parameters.

This class provides functions beyond the specified interface for getting and setting solver parameters.

Parameters
  • robot_description_path (str) – path to a robot description yaml file describing the cspace of the robot and other relevant parameters

  • urdf_path (str) – path to a URDF file describing the robot

  • robot_description (Optional[lula.RobotDescription]) – An initialized lula.RobotDescription object. Other Lula-based classes such as RmpFlow may use a lula.RobotDescription object that they have already created to initialize a LulaKinematicsSolver. When specified, the provided file paths are unused. Defaults to None.

set_robot_base_pose(robot_position: numpy.array, robot_orientation: numpy.array)None

Update position of the robot base. This will be used to compute kinematics relative to the USD stage origin.

Parameters
  • robot_positions (np.array) – (3 x 1) translation vector describing the translation of the robot base relative to the USD stage origin. The translation vector should be specified in the units of the USD stage

  • robot_orientation (np.array) – (4 x 1) quaternion describing the orientation of the robot base relative to the USD stage global frame

get_joint_names()List[str]

Return a list containing the names of all joints in the given kinematic structure. The order of this list determines the order in which the joint positions are expected in compute_forward_kinematics(joint_positions,…) and the order in which they are returned in compute_inverse_kinematics()

Returns

Names of all joints in the robot

Return type

List[str]

get_all_frame_names()List[str]

Return a list of all the frame names in the given kinematic structure

Returns

All frame names in the kinematic structure. Any of which can be used to compute forward or inverse kinematics.

Return type

List[str]

compute_forward_kinematics(frame_name: str, joint_positions: numpy.array, position_only: Optional[bool] = False)Tuple[numpy.array, numpy.array]

Compute the position of a given frame in the robot relative to the USD stage global frame

Parameters
  • frame_name (str) – Name of robot frame on which to calculate forward kinematics

  • joint_positions (np.array) – Joint positions for the joints returned by get_joint_names()

  • position_only (bool) – Lula Kinematics ignore this flag and always computes both position and orientation

Returns

frame_positions: (3x1) vector describing the translation of the frame relative to the USD stage origin

frame_rotation: (3x3) rotation matrix describing the rotation of the frame relative to the USD stage global frame

Return type

Tuple[np.array,np.array]

compute_inverse_kinematics(frame_name: str, target_position: numpy.array, target_orientation: Optional[numpy.array] = None, warm_start: Optional[numpy.array] = None, position_tolerance: Optional[float] = None, orientation_tolerance: Optional[float] = None)Tuple[numpy.array, bool]

Compute joint positions such that the specified robot frame will reach the desired translations and rotations. Lula Kinematics interpret the orientation tolerance as being the maximum rotation separating any standard axes. e.g. For a tolerance of .1: The X axes, Y axes, and Z axes of the rotation matrices may independently be as far as .1 radians apart

Default values for position and orientation tolerances may be seen and changed with setter and getter functions.

Parameters
  • frame_name (str) – name of the target frame for inverse kinematics

  • target_position (np.array) – target translation of the target frame (in stage units) relative to the USD stage origin

  • target_orientation (np.array) – target orientation of the target frame relative to the USD stage global frame. Defaults to None.

  • warm_start (np.array) – a starting position that will be used when solving the IK problem. If default cspace seeds have been set, the warm start will be given priority, but the default seeds will still be used. Defaults to None.

  • position_tolerance (float) – l-2 norm of acceptable position error (in stage units) between the target and achieved translations. Defaults to None.

  • tolerance (orientation) – magnitude of rotation (in radians) separating the target orientation from the achieved orienatation. orientation_tolerance is well defined for values between 0 and pi. Defaults to None.

Returns

joint_positions: in the order specified by get_joint_names() which result in the target frame acheiving the desired position

success: True if the solver converged to a solution within the given tolerances

Return type

Tuple[np.array,bool]

supports_collision_avoidance()bool

Lula Inverse Kinematics do not support collision avoidance with USD obstacles

Returns

Always False

Return type

bool

set_orientation_weight(weight: float)None

Orientation weight describes a ratio of importance betwee hitting the position and orientation target. A weight of 0 implies that the solver cares only about the orientation target. When no orientation target is given to compute_inverse_kinematics(), a weight of 0 is automatically used over the default.

Parameters

weight (float) – Ratio describing the relative importance of the orientation target vs. the position target when solving IK

set_default_orientation_tolerance(tolerance: float)None

Default orientation tolerance to be used when calculating IK when none is specified

Parameters

tolerance (float) – magnitude of rotation (in radians) separating the target orientation from the achieved orienatation. orientation_tolerance is well defined for values between 0 and pi.

set_default_position_tolerance(tolerance: float)None

Default position tolerance to be used when calculating IK when none is specified

Parameters

tolerance (float) – l-2 norm of acceptable position error (in stage units) between the target and achieved translations

set_max_iterations(max_iterations: int)None

Set the maximum number of iterations that the IK solver will attempt before giving up

Parameters

max_iterations (int) – maximum number of iterations that the IK solver will attempt before giving up

set_descent_termination_delta(delta: float)None

Set the minimum delta between two solutions at which the IK solver may terminate due to the solution not improving anymore

Parameters

delta (float) – minimum delta between two solutions at which the IK solver may terminate due to the solution not improving anymore

set_default_cspace_seeds(seeds: numpy.array)None

Set a list of cspace seeds that the solver may use as starting points for solutions

Parameters

seeds (np.array) – An N x num_dof list of cspace seeds

get_orientation_weight()float

Orientation weight describes a ratio of importance betwee hitting the position and orientation target. A weight of 0 implies that the solver cares only about the orientation target. When no orientation target is given to compute_inverse_kinematics(), a weight of 0 is automatically used over the default.

Returns

Ratio describing the relative importance of the orientation target vs. the position target when solving IK

Return type

float

get_default_orientation_tolerance()float

Get the default orientation tolerance to be used when calculating IK when none is specified

Returns

magnitude of rotation (in radians) separating the target orientation from the achieved orienatation.

orientation_tolerance is well defined for values between 0 and pi.

Return type

float

get_default_position_tolerance()float

Get the default position tolerance to be used when calculating IK when none is specified

Returns

l-2 norm of acceptable position error (in stage units) between the target and achieved translations

Return type

float

get_max_iterations()int

Get the maximum number of iterations that the IK solver will attempt before giving up

Returns

maximum number of iterations that the IK solver will attempt before giving up

Return type

int

get_descent_termination_delta()float

Get the minimum delta between two solutions at which the IK solver may terminate due to the solution not improving anymore

Returns

minimum delta between two solutions at which the IK solver may terminate due to the solution not improving anymore

Return type

float

get_default_cspace_seeds()List[numpy.array]

Get a list of cspace seeds that the solver may use as starting points for solutions

Returns

An N x num_dof list of cspace seeds

Return type

List[np.array]

ArticulationKinematicsSolver

class ArticulationKinematicsSolver(robot_articulation: omni.isaac.core.articulations.articulation.Articulation, kinematics_solver: omni.isaac.motion_generation.kinematics_interface.KinematicsSolver, end_effector_frame_name: str)

Wrapper class for computing robot kinematics in a way that is easily transferable to the simulated robot Articulation. A KinematicsSolver computes FK and IK at any frame, possibly only using a subset of joints available on the simulated robot. This wrapper simplifies computing the current position of the simulated robot’s end effector, as well as wrapping an IK result in an ArticulationAction that is recognized by the robot Articulation

Parameters
  • robot_articulation (Articulation) – Initialized robot Articulation object representing the simulated USD robot

  • kinematics_solver (KinematicsSolver) – An instance of a class that implements the KinematicsSolver

  • end_effector_frame_name (str) – The name of the robot’s end effector frame. This frame must appear in kinematics_solver.get_all_frame_names()

compute_end_effector_pose(position_only=False)Tuple[numpy.array, numpy.array]

Compute the pose of the robot end effector using the simulated robot’s current joint positions

Parameters

position_only (bool) – If True, only the frame positions need to be calculated. The returned rotation may be left undefined.

Returns

position: Translation vector describing the translation of the robot end effector relative to the USD global frame (in stage units)

orientation: Quaternion describing the rotation of the robot end effector frame relative to the USD stage origin

Return type

Tuple[np.array,np.array]

compute_inverse_kinematics(target_position: numpy.array, target_orientation: Optional[numpy.array] = None, position_tolerance: Optional[float] = None, orientation_tolerance: Optional[float] = None)Tuple[omni.isaac.core.utils.types.ArticulationAction, bool]

Compute inverse kinematics for the end effector frame using the current robot position as a warm start. The result is returned in an articulation action that can be directly applied to the robot.

Parameters
  • target_position (np.array) – target translation of the target frame (in stage units) relative to the USD stage origin

  • target_orientation (np.array) – target orientation of the target frame relative to the USD stage global frame. Defaults to None.

  • position_tolerance (float) – l-2 norm of acceptable position error (in stage units) between the target and achieved translations. Defaults to None.

  • tolerance (orientation) – magnitude of rotation (in radians) separating the target orientation from the achieved orienatation. orientation_tolerance is well defined for values between 0 and pi. Defaults to None.

Returns

ik_result: An ArticulationAction that can be applied to the robot to move the end effector frame to the desired position.

success: Solver converged successfully

Return type

Tuple[ArticulationAction, bool]

set_end_effector_frame(end_effector_frame_name: str)None

Set the name for the end effector frame. If the frame is not recognized by the internal KinematicsSolver instance, an error will be thrown

Parameters

end_effector_frame_name (str) – Name of the robot end effector frame.

get_end_effector_frame()str

Get the end effector frame

Returns

Name of the end effector frame

Return type

str

get_joints_subset()omni.isaac.motion_generation.articulation_subset.ArticulationSubset
Returns

A wrapper class for querying USD robot joint states in the order expected by the kinematics solver

Return type

ArticulationSubset

get_kinematics_solver()omni.isaac.motion_generation.kinematics_interface.KinematicsSolver

Get the underlying KinematicsSolver instance used by this class.

Returns

A class that can solve forward and inverse kinematics for a specified robot.

Return type

KinematicsSolver

ArticulationSubset

class ArticulationSubset(robot_articulation: omni.isaac.core.articulations.articulation.Articulation, view_joint_names: List[str])

A utility class for viewing a subset of the joints in a robot Articulation object. This class can be helpful in two ways:

  1. The order of joints returned by a robot Articulation may not match the order of joints expected by a function

  2. A function may only care about a subset of the joint states that are returned by a robot Articulation.

Example

Suppose the robot Articulation returns positions [0,1,2] for joints [“A”,”B”,”C”], and suppose that we pass view_joint_names = [“B”,”A”].

ArticulationSubset.get_joint_positions() -> [1,0]

ArticulationSubset.map_to_articulation_order([1,0]) -> [0,1,None]

Parameters
  • robot_articulation (Articulation) – An initialized Articulation object representing the simulated robot

  • view_joint_names (List[str]) – A list of joint names whose order determines the order of the joints returned by functions like get_joint_positions()

get_joint_positions()numpy.array

Get joint positions for the joint names that were passed into this articulation view on initialization. The indices of the joint positions returned correspond to the indices of the joint names.

Returns

joint positions

Return type

np.array

get_joint_velocities()numpy.array

Get joint velocities for the joint names that were passed into this articulation view on initialization. The indices of the joint velocities returned correspond to the indices of the joint names.

Returns

joint velocities

Return type

np.array

get_joint_efforts()numpy.array

Get joint efforts for the joint names that were passed into this articulation view on initialization. The indices of the joint efforts returned correspond to the indices of the joint names.

Returns

joint efforts

Return type

np.array

map_to_articulation_order(joint_values: numpy.array)numpy.array

Map a set of joint values to a format consumable by the robot Articulation.

Parameters

joint_values (np.array) –

a set of joint values corresponding to the view_joint_names used to initialize this class. joint_values may be either one or two dimensional.

If one dimensional with shape (k,): A vector will be returned with length (self._robot_articulation.num_dof) that may be consumed by the robot Articulation in an ArticulationAction.

If two dimensional with shape (N, k): A matrix will be returned with shape (N, self._robot_articulation.num_dof) that may be converted to N ArticulationActions

Returns

a set of joint values that is padded with None to match the shape and order expected by the robot Articulation.

Return type

np.array

get_joint_subset_indices()numpy.array

Accessor for the joint indices for this subset. These are the indices into the full articulation degrees of freedom corresponding to this subset of joints.

Returns

An array of joint indices defining the subset.

Return type

np.array

Motion Policy Base Controller

class MotionPolicyController(name: str, articulation_motion_policy: omni.isaac.motion_generation.articulation_motion_policy.ArticulationMotionPolicy)

A Controller that steps using an arbitrary MotionPolicy

Parameters
  • name (str) – name of this controller

  • articulation_motion_policy (ArticulationMotionPolicy) – a wrapper around a MotionPolicy for computing ArticulationActions that can be directly applied to the robot

add_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>, static: bool = False)None

Add an object from omni.isaac.core.objects as an obstacle to the motion_policy

Parameters
  • obstacle (omni.isaac.core.objects) – Dynamic, Visual, or Fixed object from omni.isaac.core.objects

  • static (bool) – If True, the obstacle may be assumed by the MotionPolicy to remain stationary over time

forward(target_end_effector_position: numpy.ndarray, target_end_effector_orientation: Optional[numpy.ndarray] = None)omni.isaac.core.utils.types.ArticulationAction

Compute an ArticulationAction representing the desired robot state for the next simulation frame

Parameters
  • target_translation (nd.array) – Translation vector (3x1) for robot end effector. Target translation should be specified in the same units as the USD stage, relative to the stage origin.

  • target_orientation (Optional[np.ndarray], optional) – Quaternion of desired rotation for robot end effector relative to USD stage global frame. Target orientation defaults to None, which means that the robot may reach the target with any orientation.

Returns

A wrapper object containing the desired next state for the robot

Return type

ArticulationAction

get_articulation_motion_policy()omni.isaac.motion_generation.articulation_motion_policy.ArticulationMotionPolicy

Get ArticulationMotionPolicy that was passed to this class on initialization

Returns

a wrapper around a MotionPolicy for computing ArticulationActions that can be directly applied to the robot

Return type

ArticulationMotionPolicy

get_motion_policy()omni.isaac.motion_generation.motion_policy_interface.MotionPolicy

Get MotionPolicy object that is being used to generate robot motions

Returns

An instance of a MotionPolicy that is being used to compute robot motions

Return type

MotionPolicy

remove_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>)None

Remove and added obstacle from the motion_policy

Parameters

obstacle (omni.isaac.core.objects) – Object from omni.isaac.core.objects that has been added to the motion_policy

reset()None

Wheel Base Pose Controller

class WheelBasePoseController(name: str, open_loop_wheel_controller: omni.isaac.core.controllers.base_controller.BaseController, is_holonomic: bool = False)

[summary]

Parameters
  • name (str) – [description]

  • open_loop_wheel_controller (BaseController) – A controller that takes in a command of [longitudinal velocity, steering angle] and returns the ArticulationAction to be applied to the wheels if non holonomic. and [longitudinal velocity, latitude velocity, steering angle] if holonomic.

  • is_holonomic (bool, optional) – [description]. Defaults to False.

forward(start_position: numpy.ndarray, start_orientation: numpy.ndarray, goal_position: numpy.ndarray, lateral_velocity: float = 0.2, yaw_velocity: float = 0.5, heading_tol: float = 0.05, position_tol: float = 0.04)omni.isaac.core.utils.types.ArticulationAction

[summary]

Parameters
  • start_position (np.ndarray) – [description]

  • start_orientation (np.ndarray) – [description]

  • goal_position (np.ndarray) – [description]

  • lateral_velocity (float, optional) – [description]. Defaults to 20.0.

  • yaw_velocity (float, optional) – [description]. Defaults to 0.5.

  • heading_tol (float, optional) – [description]. Defaults to 0.05.

  • position_tol (float, optional) – [description]. Defaults to 4.0.

Returns

[description]

Return type

ArticulationAction

reset()None

[summary]