[isaacsim.robot.manipulators] Isaac Sim Manipulators#
Warning
Deprecation: Extension deprecated since Isaac Sim 6.0.0. Refer to isaacsim.robot.experimental.manipulators.examples for recommended alternatives.
Version: 3.4.4
Overview#
Deprecated since version 6.0.0: This extension is deprecated. Refer to isaacsim.robot.experimental.manipulators.examples for recommended alternatives.
The isaacsim.robot.manipulators extension provides high-level Python classes for controlling robotic manipulators in Isaac Sim. This extension covers the complete manipulator stack: robot representation, gripper abstractions, task-level controllers, and an OmniGraph node for gripper control.
Key Components#
SingleManipulator#
The SingleManipulator class serves as the primary interface for manipulator control, built on top of the articulation system. It encapsulates a complete manipulator system consisting of the robotic arm, end effector, and optional gripper components.
Key features include:
End Effector Tracking: Monitors the rigid body corresponding to the end effector through the
end_effectorproperty, enabling access to world pose and motion dataGripper Integration: Optional gripper attachment through the
gripperproperty for pick-and-place operationsPhysics Integration: Utilizes PhysX tensor API through the
initialize()method for efficient physics simulationState Management: Provides
post_reset()functionality to restore default states after timeline resets
The class inherits from SingleArticulation, extending it with manipulator-specific functionality while maintaining compatibility with the broader articulation framework.
Grippers#
The extension provides an abstract gripper framework and two concrete implementations:
Gripper is the abstract base class for all gripper types. It extends SingleRigidPrim and defines the interface for opening, closing, and querying gripper state. All gripper implementations must provide open(), close(), get_action(), and state management methods.
ParallelGripper controls two-finger parallel grippers through joint position control. It supports configurable open/closed joint positions, action deltas for incremental movement, and optional mimic joint mode where only a single drive joint is commanded.
SurfaceGripper wraps the surface gripper physics interface for suction-cup style grippers. It manages gripper state through the isaacsim.robot.surface_gripper C++ backend, translating high-level open/close commands into the underlying surface gripper API calls.
Controllers#
PickPlaceController implements a state machine that manages pick-and-place operations through a sequence of predefined phases. These phases include moving to a picking position, approaching and grasping the object, lifting, moving to the target location, and placing the object. It coordinates end-effector control and gripper actions across all phases.
StackingController extends the pick-and-place workflow to stack multiple objects in a specified order. It sequences PickPlaceController calls to move objects from their initial positions onto a growing stack.
Integration#
The extension builds upon isaacsim.core.api for base articulation and controller classes, and isaacsim.robot.surface_gripper for the surface gripper physics backend. The controllers and grippers are designed to work together with SingleManipulator, providing a complete manipulator control stack from low-level gripper actuation to high-level task execution.
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.manipulators
Define the next entry under [dependencies] in an experience (.kit) file or an extension configuration (extension.toml) file.
[dependencies]
"isaacsim.robot.manipulators" = {}
Open the Window > Extensions menu in a running application instance and search for isaacsim.robot.manipulators.
Then, toggle the enable control button if it is not already active.
Python API#
manipulators
Provides high level functions to set/ get properties and actions of a manipulator with a single end effector. |
controllers
A simple pick and place state machine for tutorials. |
|
Controller for stacking objects in a specified order. |
grippers
Provides high level functions to set/ get properties and actions of a gripper. |
|
Provides high level functions to set/ get properties and actions of a parallel gripper. |
|
Provides high level functions to set/ get properties and actions of a surface gripper. |
Manipulators#
- class SingleManipulator(
- prim_path: str,
- end_effector_prim_path: str,
- name: str = 'single_manipulator',
- position: Sequence[float] | None = None,
- translation: Sequence[float] | None = None,
- orientation: Sequence[float] | None = None,
- scale: Sequence[float] | None = None,
- visible: bool | None = None,
- gripper: Gripper = None,
Bases:
SingleArticulationProvides high level functions to set/ get properties and actions of a manipulator with a single end effector.
and optionally a gripper.
- Parameters:
prim_path – Prim path of the Prim to encapsulate or create.
end_effector_prim_path – End effector prim path to be used to track the rigid body that corresponds to the end effector. One of the following args can be specified only: end_effector_prim_name or end_effector_prim_path.
name – Shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene.
position – Position in the world frame of the prim. shape is (3, ).
translation – Translation in the local frame of the prim (with respect to its parent prim). shape is (3, ).
orientation – Quaternion orientation in the world/ local frame of the prim (depends if translation or position is specified). quaternion is scalar-first (w, x, y, z). shape is (4, ).
scale – Local scale to be applied to the prim’s dimensions. shape is (3, ).
visible – Set to false for an invisible prim in the stage while rendering.
gripper – Gripper to be used with the manipulator.
- apply_action(
- control_actions: ArticulationAction,
Apply joint positions, velocities and/or efforts to control an articulation.
- Parameters:
control_actions – Actions to be applied for next physics step.
Hint
High stiffness makes the joints snap faster and harder to the desired target, and higher damping smoothes but also slows down the joint’s movement to target
For position control, set relatively high stiffness and low damping (to reduce vibrations)
For velocity control, stiffness must be set to zero with a non-zero damping
For effort control, stiffness and damping must be set to zero
Example:
>>> from isaacsim.core.utils.types import ArticulationAction >>> >>> # move all the robot joints to the indicated position >>> action = ArticulationAction(joint_positions=np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04])) >>> prim.apply_action(action) >>> >>> # close the robot fingers: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0 >>> action = ArticulationAction(joint_positions=np.array([0.0, 0.0]), joint_indices=np.array([7, 8])) >>> prim.apply_action(action)
- apply_visual_material(
- visual_material: VisualMaterial,
- weaker_than_descendants: bool = False,
Apply visual material to the held prim and optionally its descendants.
- Parameters:
visual_material – Visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.
weaker_than_descendants – True if the material shouldn’t override the descendants materials, otherwise False.
Example:
>>> from isaacsim.core.api.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- get_angular_velocity() ndarray#
Angular velocity of the root articulation prim.
- Returns:
3D angular velocity vector. Shape (3,).
Example:
>>> prim.get_angular_velocity() [0. 0. 0.]
- get_applied_action() ArticulationAction#
Last applied action.
- Returns:
Last applied action. Note that a dictionary is used as the object’s string representation.
Example:
>>> # last applied action: joint_positions -> [0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04] >>> prim.get_applied_action() {'joint_positions': [0.0, -1.0, 0.0, -2.200000047683716, 0.0, 2.4000000953674316, 0.800000011920929, 0.03999999910593033, 0.03999999910593033], 'joint_velocities': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], 'joint_efforts': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}
- get_applied_joint_efforts(
- joint_indices: list | ndarray | None = None,
Get the efforts applied to the joints set by the
set_joint_effortsmethod.- Parameters:
joint_indices – indices to specify which joints to read. Defaults to None (all joints)
- Raises:
Exception – If the handlers are not initialized
- Returns:
all or selected articulation joint applied efforts
Example:
>>> # get all applied joint efforts >>> prim.get_applied_joint_efforts() [ 0. 0. 0. 0. 0. 0. 0. 0. 0.] >>> >>> # get finger applied efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_applied_joint_efforts(joint_indices=np.array([7, 8])) [0. 0.]
- get_applied_visual_material() VisualMaterial#
Return the current applied visual material in case it was applied using apply_visual_material.
or it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.
- Returns:
The current applied visual material if its type is currently supported.
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <isaacsim.core.api.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_articulation_body_count() int#
Get the number of bodies (links) that make up the articulation.
- Returns:
Amount of bodies.
Example:
>>> prim.get_articulation_body_count() 12
- get_articulation_controller() ArticulationController#
Get the articulation controller.
Note
If no
articulation_controllerwas passed during class instantiation, a default controller of typeArticulationController(a Proportional-Derivative controller that can apply position targets, velocity targets and efforts) will be used- Returns:
Articulation controller.
Example:
>>> prim.get_articulation_controller() <isaacsim.core.api.controllers.articulation_controller.ArticulationController object at 0x7f04a0060190>
- get_default_state() XFormPrimState#
Get the default prim states (spatial position and orientation).
- Returns:
An object that contains the default state of the prim (position and orientation)
Example:
>>> state = prim.get_default_state() >>> state <isaacsim.core.utils.types.XFormPrimState object at 0x7f33addda650> >>> >>> state.position [-4.5299529e-08 -1.8347054e-09 -2.8610229e-08] >>> state.orientation [1. 0. 0. 0.]
- get_dof_index(dof_name: str) int#
Get a DOF index given its name.
- Parameters:
dof_name – Name of the DOF.
- Returns:
DOF index.
Example:
>>> prim.get_dof_index("panda_finger_joint2") 8
- get_enabled_self_collisions() uint8#
Get the enable self collisions flag (
physxArticulation:enabledSelfCollisions).- Returns:
self collisions flag (boolean interpreted as int)
Example:
>>> prim.get_enabled_self_collisions() 0
- get_joint_positions(
- joint_indices: list | ndarray | None = None,
Get the articulation joint positions.
- Parameters:
joint_indices – indices to specify which joints to read. Defaults to None (all joints)
- Returns:
all or selected articulation joint positions
Example:
>>> # get all joint positions >>> prim.get_joint_positions() [ 1.1999920e-02 -5.6962633e-01 1.3480479e-08 -2.8105433e+00 6.8284894e-06 3.0301569e+00 7.3234749e-01 3.9912373e-02 3.9999999e-02] >>> >>> # get finger positions: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_joint_positions(joint_indices=np.array([7, 8])) [0.03991237 3.9999999e-02]
- get_joint_velocities(
- joint_indices: list | ndarray | None = None,
Get the articulation joint velocities.
- Parameters:
joint_indices – indices to specify which joints to read. Defaults to None (all joints)
- Returns:
all or selected articulation joint velocities
Example:
>>> # get all joint velocities >>> prim.get_joint_velocities() [ 1.91603772e-06 -7.67638255e-03 -2.19138826e-07 1.10636465e-02 -4.63412944e-05 3.48245539e-02 8.84692147e-02 5.40335372e-04 1.02849208e-05] >>> >>> # get finger velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_joint_velocities(joint_indices=np.array([7, 8])) [5.4033537e-04 1.0284921e-05]
- get_joints_default_state() JointsState#
Default joint states (positions and velocities).
- Returns:
An object that contains the default joint positions and velocities.
Example:
>>> state = prim.get_joints_default_state() >>> state <isaacsim.core.utils.types.JointsState object at 0x7f04a0061240> >>> >>> state.positions [ 0.012 -0.57000005 0. -2.81 0. 3.037 0.785398 0.04 0.04 ] >>> state.velocities [0. 0. 0. 0. 0. 0. 0. 0. 0.]
- get_joints_state() JointsState#
Current joint states (positions and velocities).
- Returns:
An object that contains the current joint positions and velocities.
Example:
>>> state = prim.get_joints_state() >>> state <isaacsim.core.utils.types.JointsState object at 0x7f02f6df57b0> >>> >>> state.positions [ 1.1999920e-02 -5.6962633e-01 1.3480479e-08 -2.8105433e+00 6.8284894e-06 3.0301569e+00 7.3234749e-01 3.9912373e-02 3.9999999e-02] >>> state.velocities [ 1.91603772e-06 -7.67638255e-03 -2.19138826e-07 1.10636465e-02 -4.63412944e-05 245539e-02 8.84692147e-02 5.40335372e-04 1.02849208e-05]
- get_linear_velocity() ndarray#
Linear velocity of the root articulation prim.
- Returns:
3D linear velocity vector. Shape (3,).
Example:
>>> prim.get_linear_velocity() [0. 0. 0.]
- get_local_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the local frame (the prim’s parent frame).
- Returns:
First index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() ndarray#
Get prim’s scale with respect to the local frame (the parent’s frame).
- Returns:
Scale applied to the prim’s dimensions in the local frame. shape is (3, ).
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_measured_joint_efforts(
- joint_indices: list | ndarray | None = None,
Returns the efforts computed/measured by the physics solver of the joint forces in the DOF motion direction.
- Parameters:
joint_indices – indices to specify which joints to read. Defaults to None (all joints)
- Raises:
Exception – If the handlers are not initialized
- Returns:
all or selected articulation joint measured efforts
Example:
>>> # get all joint efforts >>> prim.get_measured_joint_efforts() [ 2.7897308e-06 -6.9083519e+00 -3.6398471e-06 1.9158335e+01 -4.3552645e-06 1.1866090e+00 -4.7079347e-06 3.2339853e-04 -3.2044132e-04] >>> >>> # get finger efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_measured_joint_efforts(joint_indices=np.array([7, 8])) [ 0.0003234 -0.00032044]
- get_measured_joint_forces(
- joint_indices: list | ndarray | None = None,
Get the measured joint reaction forces and torques (link incoming joint forces and torques) to external loads.
Forces and torques are reported in the local body reference frame (child joint frame of the link’s incoming joint).
Note
Since the name->index map for joints has not been exposed yet, it is possible to access the joint names and their indices through the articulation metadata.
prim._articulation_view._metadata.joint_names # list of names prim._articulation_view._metadata.joint_indices # dict of name: index
To retrieve a specific row for the link incoming joint force/torque use
joint_index + 1- Parameters:
joint_indices – indices to specify which joints to read. Defaults to None (all joints)
- Raises:
Exception – If the handlers are not initialized
- Returns:
measured joint forces and torques. Shape is (num_joint + 1, 6). Row index 0 is the incoming joint of the base link. For the last dimension the first 3 values are for forces and the last 3 for torques
Example:
>>> # get all measured joint forces and torques >>> prim.get_measured_joint_forces() [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00] [ 1.4995076e+02 4.2574748e-06 5.6364370e-04 4.8701895e-05 -6.9072924e+00 3.1881387e-05] [-2.8971717e-05 -1.0677823e+02 -6.8384506e+01 -6.9072924e+00 -5.4927128e-05 6.1222494e-07] [ 8.7120995e+01 -4.3871860e-05 -5.5795174e+01 5.3687054e-05 -2.4538563e+01 1.3333466e-05] [ 5.3519474e-05 -4.8109909e+01 6.0709282e+01 1.9157074e+01 -5.9258469e-05 8.2744418e-07] [-3.1691040e+01 2.3313689e-04 3.9990173e+01 -5.8968733e-05 -1.1863431e+00 2.2335558e-05] [-1.0809851e-04 1.5340537e+01 -1.5458489e+01 1.1863426e+00 6.1094368e-05 -1.5940281e-05] [-7.5418940e+00 -5.0814648e+00 -5.6512990e+00 -5.6385466e-05 3.8859999e-01 -3.4943256e-01] [ 4.7421460e+00 -3.1945827e+00 3.5528181e+00 5.5852943e-05 8.4794536e-03 7.6405057e-03] [ 4.0760727e+00 2.1640673e-01 -4.0513167e+00 -5.9565349e-04 1.1407082e-02 2.1432268e-06] [ 5.1680198e-03 -9.7754575e-02 -9.7093947e-02 -8.4155556e-12 -1.2910691e-12 -1.9347857e-11] [-5.1910793e-03 9.7588278e-02 -9.7106412e-02 8.4155573e-12 1.2910637e-12 -1.9347855e-11]] >>> >>> # get measured joint force and torque for the fingers >>> metadata = prim._articulation_view._metadata >>> joint_indices = 1 + np.array([ ... metadata.joint_indices["panda_finger_joint1"], ... metadata.joint_indices["panda_finger_joint2"], ... ]) >>> joint_indices [10 11] >>> prim.get_measured_joint_forces(joint_indices) [[ 5.1680198e-03 -9.7754575e-02 -9.7093947e-02 -8.4155556e-12 -1.2910691e-12 -1.9347857e-11] [-5.1910793e-03 9.7588278e-02 -9.7106412e-02 8.4155573e-12 1.2910637e-12 -1.9347855e-11]]
- get_sleep_threshold() float#
Get the threshold for articulations to enter a sleep state.
Search for Articulations and Sleeping in PhysX docs for more details
- Returns:
sleep threshold
Example:
>>> prim.get_sleep_threshold() 0.005
- get_solver_position_iteration_count() int#
Get the solver (position) iteration count for the articulation.
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
- Returns:
position iteration count
Example:
>>> prim.get_solver_position_iteration_count() 32
- get_solver_velocity_iteration_count() int#
Get the solver (velocity) iteration count for the articulation.
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
- Returns:
velocity iteration count
Example:
>>> prim.get_solver_velocity_iteration_count() 32
- get_stabilization_threshold() float#
Get the mass-normalized kinetic energy below which the articulation may participate in stabilization.
Search for Stabilization Threshold in PhysX docs for more details
- Returns:
stabilization threshold
Example:
>>> prim.get_stabilization_threshold() 0.0009999999
- get_visibility() bool#
Get the visibility of the prim in stage.
- Returns:
True if the prim is visible in stage. False otherwise.
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the world’s frame.
- Returns:
First index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() ndarray#
Get prim’s scale with respect to the world’s frame.
- Returns:
Scale applied to the prim’s dimensions in the world frame. shape is (3, ).
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- get_world_velocity() ndarray#
Get the articulation root velocity.
- Returns:
current velocity of the root prim. Shape (6,).
- initialize(
- physics_sim_view: omni.physics.tensors.SimulationView = None,
Create a physics simulation view if not passed and creates an articulation view using physX tensor api.
This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.
- Parameters:
physics_sim_view – Current physics simulation view.
- is_valid() bool#
Check if the prim path has a valid USD Prim at it.
- Returns:
True is the current prim path corresponds to a valid prim in stage. False otherwise.
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool#
Check if there is a visual material applied.
- Returns:
True if there is a visual material applied. False otherwise.
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- set_angular_velocity(
- velocity: ndarray,
Set the angular velocity of the root articulation prim.
Warning
This method will immediately set the articulation state
- Parameters:
velocity – 3D angular velocity vector. Shape (3,).
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> prim.set_angular_velocity(np.array([0.1, 0.0, 0.0]))
- set_default_state( ) None#
Set the default state of the prim (position and orientation), that will be used after each reset.
- Parameters:
position – Position in the world frame of the prim. shape is (3, ). Which means left unchanged.
orientation – Quaternion orientation in the world frame of the prim. Quaternion is scalar-first (w, x, y, z). shape is (4, ). Which means left unchanged.
Example:
>>> # configure default state >>> prim.set_default_state(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1, 0, 0, 0])) >>> >>> # set default states during post-reset >>> prim.post_reset()
- set_enabled_self_collisions(flag: bool) None#
Set the enable self collisions flag (
physxArticulation:enabledSelfCollisions).- Parameters:
flag – whether to enable self collisions
Example:
>>> prim.set_enabled_self_collisions(True)
- set_joint_efforts(
- efforts: ndarray,
- joint_indices: list | ndarray | None = None,
Set the articulation joint efforts.
Note
This method can be used for effort control. For this purpose, there must be no joint drive or the stiffness and damping must be set to zero.
- Parameters:
efforts – articulation joint efforts
joint_indices – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joint efforts to 0.0 >>> prim.set_joint_efforts(np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])) >>> >>> # set only the fingers efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 10 >>> prim.set_joint_efforts(np.array([10, 10]), joint_indices=np.array([7, 8]))
- set_joint_positions(
- positions: ndarray,
- joint_indices: list | ndarray | None = None,
Set the articulation joint positions.
Warning
This method will immediately set (teleport) the affected joints to the indicated value. Use the
apply_actionmethod to control robot joints.- Parameters:
positions – articulation joint positions
joint_indices – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joints >>> prim.set_joint_positions(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04])) >>> >>> # set only the fingers in closed position: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0 >>> prim.set_joint_positions(np.array([0.04, 0.04]), joint_indices=np.array([7, 8]))
- set_joint_velocities(
- velocities: ndarray,
- joint_indices: list | ndarray | None = None,
Set the articulation joint velocities.
Warning
This method will immediately set the affected joints to the indicated value. Use the
apply_actionmethod to control robot joints.- Parameters:
velocities – articulation joint velocities
joint_indices – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joint velocities to 0.0 >>> prim.set_joint_velocities(np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])) >>> >>> # set only the fingers velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) to -0.01 >>> prim.set_joint_velocities(np.array([-0.01, -0.01]), joint_indices=np.array([7, 8]))
- set_joints_default_state(
- positions: ndarray | None = None,
- velocities: ndarray | None = None,
- efforts: ndarray | None = None,
Set the joint default states (positions, velocities and/or efforts) to be applied after each reset.
Note
The default states will be set during post-reset (e.g., calling
.post_reset()orworld.reset()methods)- Parameters:
positions – Joint positions.
velocities – Joint velocities.
efforts – Joint efforts.
Example:
>>> # configure default joint states >>> prim.set_joints_default_state( ... positions=np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), ... velocities=np.zeros(shape=(prim.num_dof,)), ... efforts=np.zeros(shape=(prim.num_dof,)) ... ) >>> >>> # set default states during post-reset >>> prim.post_reset()
- set_linear_velocity(
- velocity: ndarray,
Set the linear velocity of the root articulation prim.
Warning
This method will immediately set the articulation state
- Parameters:
velocity – 3D linear velocity vector. Shape (3,).
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> prim.set_linear_velocity(np.array([0.1, 0.0, 0.0]))
- set_local_pose( ) None#
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
translation – Translation in the local frame of the prim (with respect to its parent prim). shape is (3, ).
orientation – Quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(
- scale: Sequence[float] | None,
Set prim’s scale with respect to the local frame (the prim’s parent frame).
- Parameters:
scale – Scale to be applied to the prim’s dimensions. shape is (3, ).
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_sleep_threshold(threshold: float) None#
Set the threshold for articulations to enter a sleep state.
Search for Articulations and Sleeping in PhysX docs for more details
- Parameters:
threshold – sleep threshold
Example:
>>> prim.set_sleep_threshold(0.01)
- set_solver_position_iteration_count(
- count: int,
Set the solver (position) iteration count for the articulation.
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
Warning
Setting a higher number of iterations may improve the fidelity of the simulation, although it may affect its performance.
- Parameters:
count – position iteration count
Example:
>>> prim.set_solver_position_iteration_count(64)
- set_solver_velocity_iteration_count(
- count: int,
Set the solver (velocity) iteration count for the articulation.
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
Warning
Setting a higher number of iterations may improve the fidelity of the simulation, although it may affect its performance.
- Parameters:
count – velocity iteration count
Example:
>>> prim.set_solver_velocity_iteration_count(64)
- set_stabilization_threshold(
- threshold: float,
Set the mass-normalized kinetic energy below which the articulation may participate in stabilization.
Search for Stabilization Threshold in PhysX docs for more details
- Parameters:
threshold – stabilization threshold
Example:
>>> prim.set_stabilization_threshold(0.005)
- set_visibility(visible: bool) None#
Set the visibility of the prim in stage.
- Parameters:
visible – Flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose( ) None#
Set prim’s pose with respect to the world’s frame.
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
position – Position in the world frame of the prim. shape is (3, ).
orientation – Quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_world_velocity(velocity: ndarray) None#
Set the articulation root velocity.
- Parameters:
velocity – linear and angular velocity to set the root prim to. Shape (6,).
- property dof_names: list[str]#
Prim names for each DOF.
- Returns:
Prim names.
Example:
>>> prim.dof_names ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7', 'panda_finger_joint1', 'panda_finger_joint2']
- property dof_properties: ndarray#
Articulation DOF properties.
DOF properties# Index
Property name
Description
0
typeDOF type: invalid/unknown/uninitialized (0), rotation (1), translation (2)
1
hasLimitsWhether the DOF has limits
2
lowerLower DOF limit (in radians or meters)
3
upperUpper DOF limit (in radians or meters)
4
driveModeDrive mode for the DOF: force (1), acceleration (2)
5
maxVelocityMaximum DOF velocity. In radians/s, or stage_units/s
6
maxEffortMaximum DOF effort. In N or N*stage_units
7
stiffnessDOF stiffness
8
dampingDOF damping
- Returns:
Named NumPy array of shape (num_dof, 9).
Example:
>>> # get properties for all DOFs >>> prim.dof_properties [(1, True, -2.8973, 2.8973, 1, 1.0000000e+01, 5220., 60000., 3000.) (1, True, -1.7628, 1.7628, 1, 1.0000000e+01, 5220., 60000., 3000.) (1, True, -2.8973, 2.8973, 1, 5.9390470e+36, 5220., 60000., 3000.) (1, True, -3.0718, -0.0698, 1, 5.9390470e+36, 5220., 60000., 3000.) (1, True, -2.8973, 2.8973, 1, 5.9390470e+36, 720., 25000., 3000.) (1, True, -0.0175, 3.7525, 1, 5.9390470e+36, 720., 15000., 3000.) (1, True, -2.8973, 2.8973, 1, 1.0000000e+01, 720., 5000., 3000.) (2, True, 0. , 0.04 , 1, 3.4028235e+38, 720., 6000., 1000.) (2, True, 0. , 0.04 , 1, 3.4028235e+38, 720., 6000., 1000.)] >>> >>> # property names >>> prim.dof_properties.dtype.names ('type', 'hasLimits', 'lower', 'upper', 'driveMode', 'maxVelocity', 'maxEffort', 'stiffness', 'damping') >>> >>> # get DOF upper limits >>> prim.dof_properties["upper"] [ 2.8973 1.7628 2.8973 -0.0698 2.8973 3.7525 2.8973 0.04 0.04 ] >>> >>> # get the last DOF (panda_finger_joint2) upper limit >>> prim.dof_properties["upper"][8] # or prim.dof_properties[8][3] 0.04
- property end_effector: SingleRigidPrim#
End effector of the manipulator.
- Returns:
End effector that can be used to get its world pose, angular velocity, etc.
- property gripper: Gripper#
Gripper of the manipulator.
- Returns:
Gripper that can be used to open or close the gripper, get its world pose or angular velocity, etc.
- property handles_initialized: bool#
Whether the articulation handler is initialized.
- Returns:
Whether the handler was initialized.
Example:
>>> prim.handles_initialized True
- property name: str | None#
Name given to the prim when instantiating it.
- Returns:
Name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool#
Used to query if the prim is a non root articulation link.
- Returns:
True if the prim itself is a non root link
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- property num_bodies: int#
Number of articulation links.
- Returns:
Number of links.
Example:
>>> prim.num_bodies 9
- property num_dof: int#
Number of degrees of freedom of the articulation.
- Returns:
Amount of DOFs.
Example:
>>> prim.num_dof 9
- property prim: pxr.Usd.Prim#
USD Prim object that this object holds.
- Returns:
USD Prim object that this object holds.
- property prim_path: str#
Prim path in the stage.
- Returns:
Prim path in the stage.
Controllers#
- class PickPlaceController(
- name: str,
- cspace_controller: BaseController,
- gripper: Gripper,
- end_effector_initial_height: float | None = None,
- events_dt: list[float] | None = None,
Bases:
BaseControllerA simple pick and place state machine for tutorials.
Each phase runs for 1 second, which is the internal time of the state machine
Dt of each phase/ event step is defined
Phase 0: Move end_effector above the cube center at the ‘end_effector_initial_height’.
Phase 1: Lower end_effector down to encircle the target cube
Phase 2: Wait for Robot’s inertia to settle.
Phase 3: close grip.
Phase 4: Move end_effector up again, keeping the grip tight (lifting the block).
Phase 5: Smoothly move the end_effector toward the goal xy, keeping the height constant.
Phase 6: Move end_effector vertically toward goal height at the ‘end_effector_initial_height’.
Phase 7: loosen the grip.
Phase 8: Move end_effector vertically up again at the ‘end_effector_initial_height’
Phase 9: Move end_effector towards the old xy position.
- Parameters:
name – Name id of the controller.
cspace_controller – A cartesian space controller that returns an ArticulationAction type.
gripper – A gripper controller for open/ close actions.
end_effector_initial_height – End effector initial picking height to start from (more info in phases above). If not defined, set to 0.3 meters.
events_dt – Dt of each phase/ event step. 10 phases dt has to be defined.
- Raises:
Exception – events dt need to be list or numpy array
Exception – events dt need have length of 10
- forward(
- picking_position: ndarray,
- placing_position: ndarray,
- current_joint_positions: ndarray,
- end_effector_offset: ndarray | None = None,
- end_effector_orientation: ndarray | None = None,
Runs the controller one step.
- Parameters:
picking_position – The object’s position to be picked in local frame.
placing_position – The object’s position to be placed in local frame.
current_joint_positions – Current joint positions of the robot.
end_effector_offset – Offset of the end effector target.
end_effector_orientation – End effector orientation while picking and placing.
- Returns:
Action to be executed by the ArticulationController.
- get_current_event() int#
Current event/ phase of the state machine.
- Returns:
Current event/ phase of the state machine.
- is_done() bool#
True if the state machine reached the last phase. Otherwise False.
- Returns:
True if the state machine reached the last phase. Otherwise False.
- is_paused() bool#
True if the state machine is paused. Otherwise False.
- Returns:
True if the state machine is paused. Otherwise False.
- reset( ) None#
Resets the state machine to start from the first phase/ event.
- Parameters:
end_effector_initial_height – End effector initial picking height to start from. If not defined, set to 0.3 meters.
events_dt – Dt of each phase/ event step. 10 phases dt has to be defined.
- Raises:
Exception – Events dt need to be list or numpy array
Exception – Events dt need have length of 10
- class StackingController(
- name: str,
- pick_place_controller: PickPlaceController,
- picking_order_cube_names: list[str],
- robot_observation_name: str,
Bases:
BaseControllerController for stacking objects in a specified order.
- Parameters:
name – Name identifier for the controller.
pick_place_controller – The underlying pick and place controller.
picking_order_cube_names – Ordered list of cube names to pick and stack.
robot_observation_name – Name key for robot observations in the observation dict.
- forward(
- observations: dict,
- end_effector_orientation: ndarray | None = None,
- end_effector_offset: ndarray | None = None,
Executes the stacking sequence by picking and placing cubes in the specified order.
- Parameters:
observations – Dictionary containing robot and cube observations including positions and joint states.
end_effector_orientation – Optional orientation for the end effector during manipulation.
end_effector_offset – Optional position offset for the end effector during manipulation.
- Returns:
Articulation action containing joint positions for the robot.
- is_done() bool#
Check if all cubes have been stacked.
- Returns:
True if all cubes have been stacked, False otherwise.
Grippers#
- class Gripper(end_effector_prim_path: str)#
Bases:
SingleRigidPrimProvides high level functions to set/ get properties and actions of a gripper.
- Parameters:
end_effector_prim_path – Prim path of the Prim that corresponds to the gripper root/ end effector.
- apply_visual_material(
- visual_material: VisualMaterial,
- weaker_than_descendants: bool = False,
Apply visual material to the held prim and optionally its descendants.
- Parameters:
visual_material – Visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.
weaker_than_descendants – True if the material shouldn’t override the descendants materials, otherwise False.
Example:
>>> from isaacsim.core.api.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- abstract close() None#
Applies actions to the articulation that closes the gripper (ex: to hold an object).
- disable_rigid_body_physics() None#
Disable the rigid body physics.
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None#
Enable the rigid body physics.
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- abstract forward(
- *args: Any,
- **kwargs: Any,
Calculates the ArticulationAction for all of the articulation joints that corresponds to a specific action.
such as “open” for an example.
- Parameters:
*args – Variable length argument list.
**kwargs – Additional keyword arguments.
- Returns:
articulation action to be passed to the articulation itself (includes all joints of the articulation).
- get_angular_velocity() ndarray#
Get the angular velocity of the rigid body.
- Returns:
current angular velocity of the the rigid prim. Shape (3,).
- get_applied_visual_material() VisualMaterial#
Return the current applied visual material in case it was applied using apply_visual_material.
or it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.
- Returns:
The current applied visual material if its type is currently supported.
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <isaacsim.core.api.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() tuple[ndarray, ndarray]#
Get the center of mass pose of the rigid body.
- Returns:
A tuple of (position, orientation) where position is the center of mass position and orientation is the center of mass orientation.
- get_current_dynamic_state() DynamicState#
Get the current rigid body state (position, orientation and linear and angular velocities).
- Returns:
the dynamic state of the rigid body prim
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <isaacsim.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- abstract get_default_state(
- *args: Any,
- **kwargs: Any,
Gets the default state of the gripper.
- Parameters:
*args – Variable length argument list.
**kwargs – Additional keyword arguments.
- Returns:
The default state of the gripper.
- get_density() float#
Get the density of the rigid body.
- Returns:
density of the rigid body.
Example:
>>> prim.get_density() 0
- get_linear_velocity() ndarray#
Get the linear velocity of the rigid body.
- Returns:
current linear velocity of the the rigid prim. Shape (3,).
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the local frame (the prim’s parent frame).
- Returns:
First index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() ndarray#
Get prim’s scale with respect to the local frame (the parent’s frame).
- Returns:
Scale applied to the prim’s dimensions in the local frame. shape is (3, ).
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float#
Get the mass of the rigid body.
- Returns:
mass of the rigid body in kg.
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float#
Get the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns:
Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool#
Get the visibility of the prim in stage.
- Returns:
True if the prim is visible in stage. False otherwise.
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the world’s frame.
- Returns:
First index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() ndarray#
Get prim’s scale with respect to the world’s frame.
- Returns:
Scale applied to the prim’s dimensions in the world frame. shape is (3, ).
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- initialize(
- physics_sim_view: omni.physics.tensors.SimulationView = None,
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.
This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.
- Parameters:
physics_sim_view – current physics simulation view.
- is_valid() bool#
Check if the prim path has a valid USD Prim at it.
- Returns:
True is the current prim path corresponds to a valid prim in stage. False otherwise.
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool#
Check if there is a visual material applied.
- Returns:
True if there is a visual material applied. False otherwise.
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- abstract open() None#
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- post_reset() None#
Reset the prim to its default state (position and orientation).
Note
For an articulation, in addition to configuring the root prim’s default position and spatial orientation (defined via the
set_default_statemethod), the joint’s positions, velocities, and efforts (defined via theset_joints_default_statemethod) are imposedExample:
>>> prim.post_reset()
- set_angular_velocity(velocity: ndarray) None#
Set the angular velocity of the rigid body in stage.
Warning
This method will immediately set the rigid body state
- Parameters:
velocity – angular velocity to set the rigid prim to. Shape (3,).
- set_com(
- position: ndarray,
- orientation: ndarray,
Set the center of mass pose of the rigid body.
- Parameters:
position – center of mass position. Shape (3,).
orientation – center of mass orientation. Shape (4,).
- abstract set_default_state(
- *args: Any,
- **kwargs: Any,
Sets the default state of the gripper.
- Parameters:
*args – Variable length argument list.
**kwargs – Additional keyword arguments.
- set_density(density: float) None#
Set the density of the rigid body.
- Parameters:
density – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: ndarray) None#
Set the linear velocity of the rigid body in stage.
Warning
This method will immediately set the rigid prim state
- Parameters:
velocity – linear velocity to set the rigid prim to. Shape (3,).
- set_local_pose( ) None#
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
translation – Translation in the local frame of the prim (with respect to its parent prim). shape is (3, ).
orientation – Quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(
- scale: Sequence[float] | None,
Set prim’s scale with respect to the local frame (the prim’s parent frame).
- Parameters:
scale – Scale to be applied to the prim’s dimensions. shape is (3, ).
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None#
Set the mass of the rigid body.
- Parameters:
mass – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None#
Set the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters:
threshold – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None#
Set the visibility of the prim in stage.
- Parameters:
visible – Flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose( ) None#
Set prim’s pose with respect to the world’s frame.
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
position – Position in the world frame of the prim. shape is (3, ).
orientation – Quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- property name: str | None#
Name given to the prim when instantiating it.
- Returns:
Name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool#
Used to query if the prim is a non root articulation link.
- Returns:
True if the prim itself is a non root link
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- property prim: pxr.Usd.Prim#
USD Prim object that this object holds.
- Returns:
USD Prim object that this object holds.
- property prim_path: str#
Prim path in the stage.
- Returns:
Prim path in the stage.
- class ParallelGripper(
- end_effector_prim_path: str,
- joint_prim_names: list[str],
- joint_opened_positions: ndarray,
- joint_closed_positions: ndarray,
- action_deltas: ndarray = None,
- use_mimic_joints: bool = False,
Bases:
GripperProvides high level functions to set/ get properties and actions of a parallel gripper.
(a gripper that has two fingers).
- Parameters:
end_effector_prim_path – Prim path of the Prim that corresponds to the gripper root/ end effector.
joint_prim_names – The left finger joint prim name and the right finger joint prim name respectively.
joint_opened_positions – Joint positions of the left finger joint and the right finger joint respectively when opened.
joint_closed_positions – Joint positions of the left finger joint and the right finger joint respectively when closed.
action_deltas – Deltas to apply for finger joint positions when opening or closing the gripper.
use_mimic_joints – Whether to use mimic joints. If True, only the drive joint is used.
- apply_action(
- control_actions: ArticulationAction,
Applies actions to all the joints of an articulation that corresponds to the ArticulationAction of the finger joints only.
- Parameters:
control_actions – ArticulationAction for the left finger joint and the right finger joint respectively.
- apply_visual_material(
- visual_material: VisualMaterial,
- weaker_than_descendants: bool = False,
Apply visual material to the held prim and optionally its descendants.
- Parameters:
visual_material – Visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.
weaker_than_descendants – True if the material shouldn’t override the descendants materials, otherwise False.
Example:
>>> from isaacsim.core.api.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- disable_rigid_body_physics() None#
Disable the rigid body physics.
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None#
Enable the rigid body physics.
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- forward(
- action: str,
Calculates the ArticulationAction for all of the articulation joints that corresponds to “open”.
or “close” actions.
- Parameters:
action – “open” or “close” as an abstract action.
- Raises:
Exception – If action is not “open” or “close”.
- Returns:
Articulation action to be passed to the articulation itself (includes all joints of the articulation).
- get_action_deltas() ndarray#
Deltas that will be applied for finger joint positions when opening or closing the gripper.
- Returns:
Deltas for left and right finger joints.
- get_angular_velocity() ndarray#
Get the angular velocity of the rigid body.
- Returns:
current angular velocity of the the rigid prim. Shape (3,).
- get_applied_visual_material() VisualMaterial#
Return the current applied visual material in case it was applied using apply_visual_material.
or it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.
- Returns:
The current applied visual material if its type is currently supported.
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <isaacsim.core.api.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() tuple[ndarray, ndarray]#
Get the center of mass pose of the rigid body.
- Returns:
A tuple of (position, orientation) where position is the center of mass position and orientation is the center of mass orientation.
- get_current_dynamic_state() DynamicState#
Get the current rigid body state (position, orientation and linear and angular velocities).
- Returns:
the dynamic state of the rigid body prim
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <isaacsim.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() ndarray#
Gets the default state of the gripper.
- Returns:
Joint positions of the left finger joint and the right finger joint respectively.
- get_density() float#
Get the density of the rigid body.
- Returns:
density of the rigid body.
Example:
>>> prim.get_density() 0
- get_joint_positions() ndarray#
Joint positions of the left finger joint and the right finger joint respectively.
- Returns:
Joint positions of the left finger joint and the right finger joint respectively.
- get_linear_velocity() ndarray#
Get the linear velocity of the rigid body.
- Returns:
current linear velocity of the the rigid prim. Shape (3,).
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the local frame (the prim’s parent frame).
- Returns:
First index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() ndarray#
Get prim’s scale with respect to the local frame (the parent’s frame).
- Returns:
Scale applied to the prim’s dimensions in the local frame. shape is (3, ).
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float#
Get the mass of the rigid body.
- Returns:
mass of the rigid body in kg.
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float#
Get the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns:
Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool#
Get the visibility of the prim in stage.
- Returns:
True if the prim is visible in stage. False otherwise.
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the world’s frame.
- Returns:
First index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() ndarray#
Get prim’s scale with respect to the world’s frame.
- Returns:
Scale applied to the prim’s dimensions in the world frame. shape is (3, ).
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- initialize(
- articulation_apply_action_func: Callable,
- get_joint_positions_func: Callable,
- set_joint_positions_func: Callable,
- dof_names: list,
- physics_sim_view: omni.physics.tensors.SimulationView = None,
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.
This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.
- Parameters:
articulation_apply_action_func – apply_action function from the Articulation class.
get_joint_positions_func – get_joint_positions function from the Articulation class.
set_joint_positions_func – set_joint_positions function from the Articulation class.
dof_names – dof names from the Articulation class.
physics_sim_view – current physics simulation view.
- Raises:
Exception – If not all gripper dof names were resolved to dof handles and dof indices.
- is_valid() bool#
Check if the prim path has a valid USD Prim at it.
- Returns:
True is the current prim path corresponds to a valid prim in stage. False otherwise.
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool#
Check if there is a visual material applied.
- Returns:
True if there is a visual material applied. False otherwise.
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- open() None#
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- set_action_deltas(value: ndarray) None#
Sets the deltas to apply for finger joint positions when opening or closing the gripper.
- Parameters:
value – deltas to apply for finger joint positions when openning or closing the gripper. [left, right].
- set_angular_velocity(velocity: ndarray) None#
Set the angular velocity of the rigid body in stage.
Warning
This method will immediately set the rigid body state
- Parameters:
velocity – angular velocity to set the rigid prim to. Shape (3,).
- set_com(
- position: ndarray,
- orientation: ndarray,
Set the center of mass pose of the rigid body.
- Parameters:
position – center of mass position. Shape (3,).
orientation – center of mass orientation. Shape (4,).
- set_default_state(
- joint_positions: ndarray,
Sets the default state of the gripper.
- Parameters:
joint_positions – Joint positions of the left finger joint and the right finger joint respectively.
- set_density(density: float) None#
Set the density of the rigid body.
- Parameters:
density – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_joint_positions(positions: ndarray) None#
Sets the joint positions of the gripper fingers.
- Parameters:
positions – Joint positions of the left finger joint and the right finger joint respectively.
- set_linear_velocity(velocity: ndarray) None#
Set the linear velocity of the rigid body in stage.
Warning
This method will immediately set the rigid prim state
- Parameters:
velocity – linear velocity to set the rigid prim to. Shape (3,).
- set_local_pose( ) None#
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
translation – Translation in the local frame of the prim (with respect to its parent prim). shape is (3, ).
orientation – Quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(
- scale: Sequence[float] | None,
Set prim’s scale with respect to the local frame (the prim’s parent frame).
- Parameters:
scale – Scale to be applied to the prim’s dimensions. shape is (3, ).
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None#
Set the mass of the rigid body.
- Parameters:
mass – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None#
Set the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters:
threshold – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None#
Set the visibility of the prim in stage.
- Parameters:
visible – Flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose( ) None#
Set prim’s pose with respect to the world’s frame.
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
position – Position in the world frame of the prim. shape is (3, ).
orientation – Quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- property active_joint_count: int#
Number of active joints based on the use_mimic_joints setting.
- Returns:
Number of active joints (1 or 2).
- property active_joint_indices: list[int]#
Indices of active joints based on the use_mimic_joints setting.
- Returns:
List of active joint indices.
- property joint_closed_positions: ndarray#
Joint positions of the left finger joint and the right finger joint respectively when closed.
- Returns:
Joint positions of the left finger joint and the right finger joint respectively when closed.
- property joint_dof_indicies: ndarray#
Joint DOF indices in the articulation of the left finger joint and the right finger joint respectively.
- Returns:
Joint DOF indices in the articulation of the left finger joint and the right finger joint respectively.
- property joint_opened_positions: ndarray#
Joint positions of the left finger joint and the right finger joint respectively when opened.
- Returns:
Joint positions of the left finger joint and the right finger joint respectively when opened.
- property joint_prim_names: list[str]#
The left finger joint prim name and the right finger joint prim name respectively.
- Returns:
The left finger joint prim name and the right finger joint prim name respectively.
- property name: str | None#
Name given to the prim when instantiating it.
- Returns:
Name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool#
Used to query if the prim is a non root articulation link.
- Returns:
True if the prim itself is a non root link
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- property prim: pxr.Usd.Prim#
USD Prim object that this object holds.
- Returns:
USD Prim object that this object holds.
- property prim_path: str#
Prim path in the stage.
- Returns:
Prim path in the stage.
- class SurfaceGripper(end_effector_prim_path: str, surface_gripper_path: str)#
Bases:
GripperProvides high level functions to set/ get properties and actions of a surface gripper.
(a suction cup for example).
- Parameters:
end_effector_prim_path – Prim path of the Prim that corresponds to the gripper root/ end effector.
surface_gripper_path – Prim path of the surface gripper.
- apply_visual_material(
- visual_material: VisualMaterial,
- weaker_than_descendants: bool = False,
Apply visual material to the held prim and optionally its descendants.
- Parameters:
visual_material – Visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.
weaker_than_descendants – True if the material shouldn’t override the descendants materials, otherwise False.
Example:
>>> from isaacsim.core.api.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- disable_rigid_body_physics() None#
Disable the rigid body physics.
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None#
Enable the rigid body physics.
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- forward(
- action: str,
Calculates the ArticulationAction for all of the articulation joints that corresponds to “open”.
or “close” actions.
- Parameters:
action – “open” or “close” as an abstract action.
- Raises:
Exception – If articulation_num_dofs is not set during initialization.
Exception – If action is not “open” or “close”.
- Returns:
Articulation action to be passed to the articulation itself (includes all joints of the articulation).
- get_angular_velocity() ndarray#
Get the angular velocity of the rigid body.
- Returns:
current angular velocity of the the rigid prim. Shape (3,).
- get_applied_visual_material() VisualMaterial#
Return the current applied visual material in case it was applied using apply_visual_material.
or it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.
- Returns:
The current applied visual material if its type is currently supported.
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <isaacsim.core.api.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() tuple[ndarray, ndarray]#
Get the center of mass pose of the rigid body.
- Returns:
A tuple of (position, orientation) where position is the center of mass position and orientation is the center of mass orientation.
- get_current_dynamic_state() DynamicState#
Get the current rigid body state (position, orientation and linear and angular velocities).
- Returns:
the dynamic state of the rigid body prim
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <isaacsim.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() dict#
Gets the default state of the gripper.
- Returns:
Key is “opened” and value would be true if the surface gripper should start in an opened state. False otherwise.
- get_density() float#
Get the density of the rigid body.
- Returns:
density of the rigid body.
Example:
>>> prim.get_density() 0
- get_linear_velocity() ndarray#
Get the linear velocity of the rigid body.
- Returns:
current linear velocity of the the rigid prim. Shape (3,).
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the local frame (the prim’s parent frame).
- Returns:
First index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() ndarray#
Get prim’s scale with respect to the local frame (the parent’s frame).
- Returns:
Scale applied to the prim’s dimensions in the local frame. shape is (3, ).
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float#
Get the mass of the rigid body.
- Returns:
mass of the rigid body in kg.
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float#
Get the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns:
Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool#
Get the visibility of the prim in stage.
- Returns:
True if the prim is visible in stage. False otherwise.
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() tuple[ndarray, ndarray]#
Get prim’s pose with respect to the world’s frame.
- Returns:
First index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() ndarray#
Get prim’s scale with respect to the world’s frame.
- Returns:
Scale applied to the prim’s dimensions in the world frame. shape is (3, ).
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- initialize(
- physics_sim_view: omni.physics.tensors.SimulationView = None,
- articulation_num_dofs: int = None,
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.
This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.
- Parameters:
physics_sim_view – Current physics simulation view.
articulation_num_dofs – Number of DOFs of the articulation.
- is_closed() bool#
Whether the gripper is in a closed state.
- Returns:
True if the gripper is closed.
- is_open() bool#
Whether the gripper is in an open state.
- Returns:
True if the gripper is open.
- is_valid() bool#
Check if the prim path has a valid USD Prim at it.
- Returns:
True is the current prim path corresponds to a valid prim in stage. False otherwise.
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool#
Check if there is a visual material applied.
- Returns:
True if there is a visual material applied. False otherwise.
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- open() None#
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- set_angular_velocity(velocity: ndarray) None#
Set the angular velocity of the rigid body in stage.
Warning
This method will immediately set the rigid body state
- Parameters:
velocity – angular velocity to set the rigid prim to. Shape (3,).
- set_com(
- position: ndarray,
- orientation: ndarray,
Set the center of mass pose of the rigid body.
- Parameters:
position – center of mass position. Shape (3,).
orientation – center of mass orientation. Shape (4,).
- set_default_state(opened: bool) None#
Sets the default state of the gripper.
- Parameters:
opened – True if the surface gripper should start in an opened state. False otherwise.
- set_density(density: float) None#
Set the density of the rigid body.
- Parameters:
density – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: ndarray) None#
Set the linear velocity of the rigid body in stage.
Warning
This method will immediately set the rigid prim state
- Parameters:
velocity – linear velocity to set the rigid prim to. Shape (3,).
- set_local_pose( ) None#
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
translation – Translation in the local frame of the prim (with respect to its parent prim). shape is (3, ).
orientation – Quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(
- scale: Sequence[float] | None,
Set prim’s scale with respect to the local frame (the prim’s parent frame).
- Parameters:
scale – Scale to be applied to the prim’s dimensions. shape is (3, ).
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None#
Set the mass of the rigid body.
- Parameters:
mass – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None#
Set the threshold for the rigid body to enter a sleep state.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters:
threshold – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None#
Set the visibility of the prim in stage.
- Parameters:
visible – Flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose( ) None#
Set prim’s pose with respect to the world’s frame.
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- Parameters:
position – Position in the world frame of the prim. shape is (3, ).
orientation – Quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- property name: str | None#
Name given to the prim when instantiating it.
- Returns:
Name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool#
Used to query if the prim is a non root articulation link.
- Returns:
True if the prim itself is a non root link
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- property prim: pxr.Usd.Prim#
USD Prim object that this object holds.
- Returns:
USD Prim object that this object holds.
- property prim_path: str#
Prim path in the stage.
- Returns:
Prim path in the stage.
Omnigraph Nodes#
The extension exposes the following Omnigraph nodes: