Core [omni.isaac.core]


Articulations

Articulation

class Articulation(prim_path: str, name: str = 'articulation', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, articulation_controller: Optional[omni.isaac.core.controllers.articulation_controller.ArticulationController] = None)

High level wrapper to deal with an articulation prim (only one articulation prim) and its attributes/properties.

Warning

The articulation object must be initialized in order to be able to operate on it. See the initialize method for more details.

Parameters
  • prim_path (str) – prim path of the Prim to encapsulate or create.

  • name (str, optional) – shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene. Defaults to “articulation”.

  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. Shape is (3, ). Defaults to None, which means left unchanged.

  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). Shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – 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, ). Defaults to None, which means left unchanged.

  • scale (Optional[Sequence[float]], optional) – local scale to be applied to the prim’s dimensions. Shape is (3, ). Defaults to None, which means left unchanged.

  • visible (bool, optional) – set to false for an invisible prim in the stage while rendering. Defaults to True.

  • articulation_controller (Optional[ArticulationController], optional) – a custom ArticulationController which inherits from it. Defaults to creating the basic ArticulationController.

Example:

>>> import omni.isaac.core.utils.stage as stage_utils
>>> from omni.isaac.core.articulations import Articulation
>>>
>>> usd_path = "/home/<user>/Documents/Assets/Robots/Franka/franka_alt_fingers.usd"
>>> prim_path = "/World/envs/env_0/panda"
>>>
>>> # load the Franka Panda robot USD file
>>> stage_utils.add_reference_to_stage(usd_path, prim_path)
>>>
>>> # wrap the prim as an articulation
>>> prim = Articulation(prim_path=prim_path, name="franka_panda")
>>> prim
<omni.isaac.core.articulations.articulation.Articulation object at 0x7fdd165bf520>
apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

Apply joint positions, velocities and/or efforts to control an articulation

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

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 omni.isaac.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: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

Example:

>>> from omni.isaac.core.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_gravity() None

Keep gravity from affecting the robot

Example:

>>> prim.disable_gravity()
property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

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: numpy.ndarray

Articulation DOF properties

DOF properties

Index

Property name

Description

0

type

DOF type: invalid/unknown/uninitialized (0), rotation (1), translation (2)

1

hasLimits

Whether the DOF has limits

2

lower

Lower DOF limit (in radians or meters)

3

upper

Upper DOF limit (in radians or meters)

4

driveMode

Drive mode for the DOF: force (1), acceleration (2)

5

maxVelocity

Maximum DOF velocity. In radians/s, or stage_units/s

6

maxEffort

Maximum DOF effort. In N or N*stage_units

7

stiffness

DOF stiffness

8

damping

DOF damping

Returns

named NumPy array of shape (num_dof, 9)

Return type

np.ndarray

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
enable_gravity() None

Gravity will affect the robot

Example:

>>> prim.enable_gravity()
get_angular_velocity() numpy.ndarray

Get the angular velocity of the root articulation prim

Returns

3D angular velocity vector. Shape (3,)

Return type

np.ndarray

Example:

>>> prim.get_angular_velocity()
[0. 0. 0.]
get_applied_action() omni.isaac.core.utils.types.ArticulationAction

Get the last applied action

Returns

last applied action. Note: a dictionary is used as the object’s string representation

Return type

ArticulationAction

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: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Get the efforts applied to the joints set by the set_joint_efforts method

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – 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

Return type

np.ndarray

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() omni.isaac.core.materials.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.

Return type

VisualMaterial

Example:

>>> # given a visual material applied
>>> prim.get_applied_visual_material()
<omni.isaac.core.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

Return type

int

Example:

>>> prim.get_articulation_body_count()
12
get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController

Get the articulation controller

Note

If no articulation_controller was passed during class instantiation, a default controller of type ArticulationController (a Proportional-Derivative controller that can apply position targets, velocity targets and efforts) will be used

Returns

articulation controller

Return type

ArticulationController

Example:

>>> prim.get_articulation_controller()
<omni.isaac.core.controllers.articulation_controller.ArticulationController object at 0x7f04a0060190>
get_default_state() omni.isaac.core.utils.types.XFormPrimState

Get the default prim states (spatial position and orientation).

Returns

an object that contains the default state of the prim (position and orientation)

Return type

XFormPrimState

Example:

>>> state = prim.get_default_state()
>>> state
<omni.isaac.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 (str) – name of the DOF

Returns

DOF index

Return type

int

Example:

>>> prim.get_dof_index("panda_finger_joint2")
8
get_enabled_self_collisions() int

Get the enable self collisions flag (physxArticulation:enabledSelfCollisions)

Returns

self collisions flag (boolean interpreted as int)

Return type

int

Example:

>>> prim.get_enabled_self_collisions()
0
get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Get the articulation joint positions

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)

Returns

all or selected articulation joint positions

Return type

np.ndarray

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: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Get the articulation joint velocities

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)

Returns

all or selected articulation joint velocities

Return type

np.ndarray

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() omni.isaac.core.utils.types.JointsState

Get the default joint states (positions and velocities).

Returns

an object that contains the default joint positions and velocities

Return type

JointsState

Example:

>>> state = prim.get_joints_default_state()
>>> state
<omni.isaac.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() omni.isaac.core.utils.types.JointsState

Get the current joint states (positions and velocities)

Returns

an object that contains the current joint positions and velocities

Return type

JointsState

Example:

>>> state = prim.get_joints_state()
>>> state
<omni.isaac.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() numpy.ndarray

Get the linear velocity of the root articulation prim

Returns

3D linear velocity vector. Shape (3,)

Return type

np.ndarray

Example:

>>> prim.get_linear_velocity()
[0. 0. 0.]
get_local_pose() Tuple[numpy.ndarray, numpy.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

Return type

Tuple[np.ndarray, np.ndarray]

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() numpy.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, ).

Return type

np.ndarray

Example:

>>> prim.get_local_scale()
[1. 1. 1.]
get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the efforts computed/measured by the physics solver of the joint forces in the DOF motion direction

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – 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

Return type

np.ndarray

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: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Get the measured joint reaction forces and torques (link incoming joint forces and torques) to external loads

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 (Optional[Union[List, np.ndarray]], optional) – 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

Return type

np.ndarray

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

Return type

float

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

Return type

int

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

Return type

int

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

Return type

float

Example:

>>> prim.get_stabilization_threshold()
0.0009999999
get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

Example:

>>> # get the visible state of an visible prim on the stage
>>> prim.get_visibility()
True
get_world_pose() Tuple[numpy.ndarray, numpy.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

Return type

Tuple[np.ndarray, np.ndarray]

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() numpy.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, ).

Return type

np.ndarray

Example:

>>> prim.get_world_scale()
[1. 1. 1.]
get_world_velocity() numpy.ndarray

Get the articulation root velocity

Returns

current velocity of the the root prim. Shape (3,).

Return type

np.ndarray

property handles_initialized: bool

Check if articulation handler is initialized

Returns

whether the handler was initialized

Return type

bool

Example:

>>> prim.handles_initialized
True
initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None

Create a physics simulation view if not passed and an articulation view using PhysX tensor API

Note

If the articulation has been added to the world scene (e.g., world.scene.add(prim)), it will be automatically initialized when the world is reset (e.g., world.reset()).

Warning

This method needs to be called after each hard reset (e.g., Stop + Play on the timeline) before interacting with any other class method.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

Example:

>>> prim.initialize()
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.

Return type

bool

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.

Return type

bool

Example:

>>> # given a visual material applied
>>> prim.is_visual_material_applied()
True
property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

Used to query if the prim is a non root articulation link

Returns

True if the prim itself is a non root link

Return type

bool

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

Return type

int

Example:

>>> prim.num_bodies
9
property num_dof: int

Number of DOF of the articulation

Returns

amount of DOFs

Return type

int

Example:

>>> prim.num_dof
9
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_state method), the joint’s positions, velocities, and efforts (defined via the set_joints_default_state method) are imposed

Example:

>>> prim.post_reset()
property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage

set_angular_velocity(velocity: numpy.ndarray) None

Set the angular velocity of the root articulation prim

Warning

This method will immediately set the articulation state

Parameters

velocity (np.ndarray) – 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_efforts

Example:

>>> prim.set_angular_velocity(np.array([0.1, 0.0, 0.0]))
set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Set the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, 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 (bool) – whether to enable self collisions

Example:

>>> prim.set_enabled_self_collisions(True)
set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.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 (np.ndarray) – articulation joint efforts

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – 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_efforts

Example:

>>> # 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: numpy.ndarray, joint_indices: Optional[Union[List, numpy.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_action method to control robot joints.

Parameters
  • positions (np.ndarray) – articulation joint positions

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – 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_efforts

Example:

>>> # 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: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

Set the articulation joint velocities

Warning

This method will immediately set the affected joints to the indicated value. Use the apply_action method to control robot joints.

Parameters
  • velocities (np.ndarray) – articulation joint velocities

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – 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_efforts

Example:

>>> # 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: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.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() or world.reset() methods)

Parameters
  • positions (Optional[np.ndarray], optional) – joint positions. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – joint velocities. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – joint efforts. Defaults to None.

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: numpy.ndarray) None

Set the linear velocity of the root articulation prim

Warning

This method will immediately set the articulation state

Parameters

velocity (np.ndarray) – 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_efforts

Example:

>>> prim.set_linear_velocity(np.array([0.1, 0.0, 0.0]))
set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) 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 (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

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: Optional[Sequence[float]]) None

Set prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

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 (float) – sleep threshold

Example:

>>> prim.set_sleep_threshold(0.01)
set_solver_position_iteration_count(count: int) None

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 (int) – 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 (int) – velocity iteration count

Example:

>>> prim.set_solver_velocity_iteration_count(64)
set_stabilization_threshold(threshold: float) None

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 (float) – stabilization threshold

Example:

>>> prim.set_stabilization_threshold(0.005)
set_visibility(visible: bool) None

Set the visibility of the prim in stage

Parameters

visible (bool) – 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(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Ses 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 (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

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: numpy.ndarray)

Set the articulation root velocity

Parameters

velocity (np.ndarray) – linear and angular velocity to set the root prim to. Shape (6,).


ArticulationView

class ArticulationView(prim_paths_expr: Union[str, List[str]], name: str = 'articulation_prim_view', positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, translations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, scales: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, visibilities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, reset_xform_properties: bool = True)

High level wrapper to deal with prims (one or many) that have the Root Articulation API applied and their attributes/properties

This class wraps all matching articulations found at the regex provided at the prim_paths_expr argument

Note

Each prim will have xformOp:orient, xformOp:translate and xformOp:scale only post-init, unless it is a non-root articulation link.

Warning

The articulation view object must be initialized in order to be able to operate on it. See the initialize method for more details.

Parameters
  • prim_paths_expr (Union[str, List[str]]) – prim paths regex to encapsulate all prims that match it. example: “/World/Env[1-5]/Franka” will match /World/Env1/Franka, /World/Env2/Franka..etc. (a non regex prim path can also be used to encapsulate one rigid prim).

  • name (str, optional) – shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene. Defaults to “articulation_prim_view”.

  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default positions in the world frame of the prims. shape is (N, 3). Defaults to None, which means left unchanged.

  • translations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default translations in the local frame of the prims (with respect to its parent prims). shape is (N, 3). Defaults to None, which means left unchanged.

  • orientations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default quaternion orientations in the world/ local frame of the prims (depends if translation or position is specified). quaternion is scalar-first (w, x, y, z). shape is (N, 4).

  • scales (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – local scales to be applied to the prim’s dimensions in the view. shape is (N, 3). Defaults to None, which means left unchanged.

  • visibilities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – set to false for an invisible prim in the stage while rendering. shape is (N,). Defaults to None.

  • reset_xform_properties (bool, optional) – True if the prims don’t have the right set of xform properties (i.e: translate, orient and scale) ONLY and in that order. Set this parameter to False if the object were cloned using using the cloner api in omni.isaac.cloner. Defaults to True.

Example:

>>> import omni.isaac.core.utils.stage as stage_utils
>>> from omni.isaac.cloner import GridCloner
>>> from omni.isaac.core.articulations import ArticulationView
>>> from pxr import UsdGeom
>>>
>>> usd_path = "/home/<user>/Documents/Assets/Robots/Franka/franka_alt_fingers.usd"
>>> env_zero_path = "/World/envs/env_0"
>>> num_envs = 5
>>>
>>> # load the Franka Panda robot USD file
>>> stage_utils.add_reference_to_stage(usd_path, prim_path=f"{env_zero_path}/panda")  # /World/envs/env_0/panda
>>>
>>> # clone the environment (num_envs)
>>> cloner = GridCloner(spacing=1.5)
>>> cloner.define_base_env(env_zero_path)
>>> UsdGeom.Xform.Define(stage_utils.get_current_stage(), env_zero_path)
>>> cloner.clone(source_prim_path=env_zero_path, prim_paths=cloner.generate_paths("/World/envs/env", num_envs))
>>>
>>> # wrap all articulations
>>> prims = ArticulationView(prim_paths_expr="/World/envs/env.*/panda", name="franka_panda_view")
>>> prims
<omni.isaac.core.articulations.articulation_view.ArticulationView object at 0x7ff174054b20>
apply_action(control_actions: omni.isaac.core.utils.types.ArticulationActions, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Apply joint positions (targets), velocities (targets) and/or efforts to control an articulation

Note

This method can be used instead of the separate set_joint_position_targets, set_joint_velocity_targets and set_joint_efforts

Parameters
  • control_actions (ArticulationActions) – actions to be applied for next physics step.

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

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 omni.isaac.core.utils.types import ArticulationActions
>>>
>>> # move all the articulation joints to the indicated position.
>>> # Since there are 5 envs, the joint positions are repeated 5 times
>>> positions = np.tile(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), (num_envs, 1))
>>> action = ArticulationActions(joint_positions=positions)
>>> prims.apply_action(action)
>>>
>>> # close the robot fingers: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0
>>> # for the first, middle and last of the 5 envs
>>> positions = np.tile(np.array([0.0, 0.0]), (3, 1))
>>> action = ArticulationActions(joint_positions=positions, joint_indices=np.array([7, 8]))
>>> prims.apply_action(action, indices=np.array([0, 2, 4]))
apply_visual_materials(visual_materials: Union[omni.isaac.core.materials.visual_material.VisualMaterial, List[omni.isaac.core.materials.visual_material.VisualMaterial]], weaker_than_descendants: Optional[Union[bool, List[bool]]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Apply visual material to the prims and optionally their prim descendants.

Parameters
  • visual_materials (Union[VisualMaterial, List[VisualMaterial]]) – visual materials to be applied to the prims. Currently supports PreviewSurface, OmniPBR and OmniGlass. If a list is provided then its size has to be equal the view’s size or indices size. If one material is provided it will be applied to all prims in the view.

  • weaker_than_descendants (Optional[Union[bool, List[bool]]], optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False. If a list of visual materials is provided then a list has to be provided with the same size for this arg as well.

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Raises
  • Exception – length of visual materials != length of prims indexed

  • Exception – length of visual materials != length of weaker descendants bools arg

Example:

>>> from omni.isaac.core.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])
... )
>>> prims.apply_visual_materials(material)
property body_names: List[str]

List of prim names for each rigid body (link) of the articulations

Returns

ordered names of bodies that corresponds to links for the articulations in the view

Return type

List[str]

Example:

>>> prims.body_names
['panda_link0', 'panda_link1', 'panda_link2', 'panda_link3', 'panda_link4', 'panda_link5',
 'panda_link6', 'panda_link7', 'panda_link8', 'panda_hand', 'panda_leftfinger', 'panda_rightfinger']
property count: int
Returns

Number of prims encapsulated in this view.

Return type

int

Example:

>>> prims.count
5
property dof_names: List[str]

List of prim names for each DOF of the articulations

Returns

ordered names of joints that corresponds to degrees of freedom for the articulations in the view

Return type

List[str]

Example:

>>> prims.dof_names
['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5',
 'panda_joint6', 'panda_joint7', 'panda_finger_joint1', 'panda_finger_joint2']
get_angular_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the angular velocities of prims in the view.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view)

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

angular velocities of the prims in the view. shape is (M, 3).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all articulation angular velocities. Returned shape is (5, 3) for the example: 5 envs, angular (3)
>>> prims.get_angular_velocities()
[[0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]]
>>>
>>> # get only the articulation angular velocities for the first, middle and last of the 5 envs
>>> # Returned shape is (5, 3) for the example: 3 envs selected, angular (3)
>>> prims.get_angular_velocities(indices=np.array([0, 2, 4]))
[[0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]]
get_applied_actions(clone: bool = True) omni.isaac.core.utils.types.ArticulationActions

Get the last applied actions

Parameters

clone (bool, optional) – True to return clones of the internal buffers. Otherwise False. Defaults to True.

Returns

current applied actions (i.e: current position targets and velocity targets)

Return type

ArticulationActions

Example:

>>> # last applied action: joint_positions -> [0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04].
>>> # Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> actions = prims.get_applied_actions()
>>> actions
<omni.isaac.core.utils.types.ArticulationActions object at 0x7f28af31d870>
>>> actions.joint_positions
[[ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]]
>>> actions.joint_velocities
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
>>> actions.joint_efforts
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
get_applied_joint_efforts(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the joint efforts of articulations in the view

This method will return the efforts set by the set_joint_efforts method

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint efforts of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all applied joint efforts. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_applied_joint_efforts()
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
>>>
>>> # get finger applied efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_applied_joint_efforts(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[0. 0.]
 [0. 0.]
 [0. 0.]]
get_applied_visual_materials(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) List[omni.isaac.core.materials.visual_material.VisualMaterial]

Get the current applied visual materials

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

a list of the current applied visual materials to the prims if its type is currently supported.

Return type

List[VisualMaterial]

Example:

>>> # get all applied visual materials. Returned size is 5 for the example: 5 envs
>>> prims.get_applied_visual_materials()
[<omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>]
>>>
>>> # get the applied visual materials for the first, middle and last of the 5 envs. Returned size is 3
>>> prims.get_applied_visual_materials(indices=np.array([0, 2, 4]))
[<omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>,
 <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f829c165de0>]
get_armatures(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get armatures for articulation joints in the view

Search for “Joint Armature” in PhysX docs for more details.

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (Optional[bool]) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint armatures for articulations in the view. shape (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get joint armatures. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_armatures()
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
>>>
>>> # get only the finger joint (panda_finger_joint1 (7) and panda_finger_joint2 (8)) armatures
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_armatures(indices=np.array([0,2,4]), joint_indices=np.array([7,8]))
[[0. 0.]
 [0. 0.]
 [0. 0.]]
get_articulation_body_count() int

Get the number of rigid bodies (links) of the articulations

Returns

maximum number of rigid bodies (links) in the articulation

Return type

int

Example:

>>> prims.get_articulation_body_count()
12
get_body_coms(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get rigid body center of mass (COM) of articulations in the view.

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body center of mass positions and orientations of articulations in the view. Position shape is (M, K, 3), orientation shape is (M, k, 4).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all body center of mass. Returned shape is (5, 12, 3) for positions and (5, 12, 4) for orientations
>>> # for the example: 5 envs, 12 rigid bodies
>>> positions, orientations = prims.get_body_coms()
>>> positions
[[[0. 0. 0.]
  [0. 0. 0.]
  ...
  [0. 0. 0.]
  [0. 0. 0.]]]
>>> orientations
[[[1. 0. 0. 0.]
  [1. 0. 0. 0.]
  ...
  [1. 0. 0. 0.]
  [1. 0. 0. 0.]]]
>>>
>>> # get finger body center of mass: panda_leftfinger (10) and panda_rightfinger (11) for the first,
>>> # middle and last of the 5 envs. Returned shape is (3, 2, 3) for positions and (3, 2, 4) for orientations
>>> positions, orientations = prims.get_body_coms(indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
>>> positions
[[[0. 0. 0.]
  [0. 0. 0.]]
 [[0. 0. 0.]
  [0. 0. 0.]]
 [[0. 0. 0.]
  [0. 0. 0.]]]
>>> orientations
[[[1. 0. 0. 0.]
  [1. 0. 0. 0.]]
 [[1. 0. 0. 0.]
  [1. 0. 0. 0.]]
 [[1. 0. 0. 0.]
  [1. 0. 0. 0.]]]
get_body_disable_gravity(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get whether the rigid bodies of articulations in the view have gravity disabled or not

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body gravity activation of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

get_body_index(body_name: str) int

Get a ridig body (link) index in the articulation view given its name

Parameters

body_name (str) – name of the ridig body to query

Returns

index of the rigid body in the articulation buffers

Return type

int

Example:

>>> # get the index of the left finger: panda_leftfinger
>>> prims.get_body_index("panda_leftfinger")
10
get_body_inertias(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get rigid body inertias of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body inertias of articulations in the view. Shape is (M, K, 9).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all body inertias. Returned shape is (5, 12, 9) for the example: 5 envs, 12 rigid bodies
>>> prims.get_body_inertias()
[[[1.2988697e-06  0.0  0.0  0.0  1.6535528e-06  0.0  0.0  0.0  2.0331163e-06]
  [1.8686389e-06  0.0  0.0  0.0  1.4378986e-06  0.0  0.0  0.0  9.0681192e-07]
  ...
  [4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]
  [4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]]]
>>>
>>> # get finger body inertias: panda_leftfinger (10) and panda_rightfinger (11)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2, 9)
>>> prims.get_body_inertias(indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
[[[4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]
  [4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]]
 ...
 [[4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]
  [4.2041304e-10  0.0  0.0  0.0  3.9026365e-10  0.0  0.0  0.0  1.3347495e-10]]]
get_body_inv_inertias(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get rigid body inverse inertias of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body inverse inertias of articulations in the view. Shape is (M, K, 9).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all body inverse inertias. Returned shape is (5, 12, 9) for the example: 5 envs, 12 rigid bodies
>>> prims.get_body_inv_inertias()
[[[7.6990012e+05  0.0  0.0  0.0  6.0475844e+05  0.0  0.0  0.0  4.9185578e+05]
  [5.3514888e+05  0.0  0.0  0.0  6.9545931e+05  0.0  0.0  0.0  1.1027645e+06]
  ...
  [2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]
  [2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]]]
>>>
>>> # get finger body inverse inertias: panda_leftfinger (10) and panda_rightfinger (11)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2, 9)
>>> prims.get_body_inv_inertias(indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
[[[2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]
  [2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]]
 ...
 [[2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]
  [2.3786132e+09  0.0  0.0  0.0  2.5623703e+09  0.0  0.0  0.0  7.4920422e+09]]]
get_body_inv_masses(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get rigid body inverse masses of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body inverse masses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all body inverse masses. Returned shape is (5, 12) for the example: 5 envs, 12 rigid bodies
>>> prims.get_body_inv_masses()
[[ 0.35534042  0.42372888  0.42025304  0.37737525  0.3710848  0.33542618  0.8860687
   2.4673615  10. 1.7910539  71.14793  71.14793]
 [ 0.35534042  0.42372888  0.42025304  0.37737525  0.3710848  0.33542618  0.8860687
   2.4673615  10. 1.7910539  71.14793  71.14793]
 [ 0.35534042  0.42372888  0.42025304  0.37737525  0.3710848  0.33542618  0.8860687
   2.4673615  10. 1.7910539  71.14793  71.14793]
 [ 0.35534042  0.42372888  0.42025304  0.37737525  0.3710848  0.33542618  0.8860687
   2.4673615  10. 1.7910539  71.14793  71.14793]
 [ 0.35534042  0.42372888  0.42025304  0.37737525  0.3710848  0.33542618  0.8860687
   2.4673615  10. 1.7910539  71.14793  71.14793]]
>>>
>>> # get finger body inverse masses: panda_leftfinger (10) and panda_rightfinger (11)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_body_inv_masses(indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
[[71.14793 71.14793]
 [71.14793 71.14793]
 [71.14793 71.14793]]
get_body_masses(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get rigid body masses of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to query. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

rigid body masses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all body masses. Returned shape is (5, 12) for the example: 5 envs, 12 rigid bodies
>>> prims.get_body_masses()
[[2.8142028  2.3599997  2.3795187  2.6498823  2.6948018  2.981282
  1.1285807  0.40529126 0.1  0.5583305  0.01405522 0.01405522]
 [2.8142028  2.3599997  2.3795187  2.6498823  2.6948018  2.981282
  1.1285807  0.40529126 0.1  0.5583305  0.01405522 0.01405522]
 [2.8142028  2.3599997  2.3795187  2.6498823  2.6948018  2.981282
  1.1285807  0.40529126 0.1  0.5583305  0.01405522 0.01405522]
 [2.8142028  2.3599997  2.3795187  2.6498823  2.6948018  2.981282
  1.1285807  0.40529126 0.1  0.5583305  0.01405522 0.01405522]
 [2.8142028  2.3599997  2.3795187  2.6498823  2.6948018  2.981282
  1.1285807  0.40529126 0.1  0.5583305  0.01405522 0.01405522]]
>>>
>>> # get finger body masses: panda_leftfinger (10) and panda_rightfinger (11)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_body_masses(indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
[[0.01405522 0.01405522]
 [0.01405522 0.01405522]
 [0.01405522 0.01405522]]
get_coriolis_and_centrifugal_forces(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the Coriolis and centrifugal forces (joint DOF forces required to counteract Coriolis and centrifugal forces for the given articulation state) of articulations in the view

Search for Coriolis and Centrifugal Forces in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

Coriolis and centrifugal forces of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all coriolis and centrifugal forces. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_coriolis_and_centrifugal_forces()
[[ 1.6842524e-06 -1.8269569e-04  5.2162073e-07 -9.7677548e-05  3.0365106e-07
   6.7375149e-06  6.1105780e-08 -4.6237556e-06 -4.1627968e-06]
 [ 1.6842524e-06 -1.8269569e-04  5.2162073e-07 -9.7677548e-05  3.0365106e-07
   6.7375149e-06  6.1105780e-08 -4.6237556e-06 -4.1627968e-06]
 [ 1.6842561e-06 -1.8269687e-04  5.2162375e-07 -9.7677454e-05  3.0365084e-07
   6.7375931e-06  6.1106007e-08 -4.6237533e-06 -4.1627954e-06]
 [ 1.6842561e-06 -1.8269687e-04  5.2162375e-07 -9.7677454e-05  3.0365084e-07
   6.7375931e-06  6.1106007e-08 -4.6237533e-06 -4.1627954e-06]
 [ 1.6842524e-06 -1.8269569e-04  5.2162073e-07 -9.7677548e-05  3.0365106e-07
   6.7375149e-06  6.1105780e-08 -4.6237556e-06 -4.1627968e-06]]
>>>
>>> # get finger joint coriolis and centrifugal forces: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_coriolis_and_centrifugal_forces(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[-4.6237556e-06 -4.1627968e-06]
 [-4.6237533e-06 -4.1627954e-06]
 [-4.6237556e-06 -4.1627968e-06]]
get_default_state() omni.isaac.core.utils.types.XFormPrimViewState

Get the default states (positions and orientations) defined with the set_default_state method

Returns

returns the default state of the prims that is used after each reset.

Return type

XFormPrimViewState

Example:

>>> state = prims.get_default_state()
>>> state
<omni.isaac.core.utils.types.XFormPrimViewState object at 0x7f82f73e3070>
>>> state.positions
[[ 1.5  -0.75  0.  ]
 [ 1.5   0.75  0.  ]
 [ 0.   -0.75  0.  ]
 [ 0.    0.75  0.  ]
 [-1.5  -0.75  0.  ]]
>>> state.orientations
[[1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]]
get_dof_index(dof_name: str) int

Get a DOF index in the joint buffers given its name

Parameters

dof_name (str) – name of the joint that corresponds to the degree of freedom to query

Returns

index of the degree of freedom in the joint buffers

Return type

int

Example:

>>> # get the index of the left finger joint: panda_finger_joint1
>>> prims.get_dof_index("panda_finger_joint1")
7
get_dof_limits() Union[numpy.ndarray, torch.Tensor]

Get the articulations DOFs limits (lower and upper)

Returns

degrees of freedom position limits. Shape is (N, num_dof, 2). For the last dimension, index 0 corresponds to lower limits and index 1 corresponds to upper limits

Return type

Union[np.ndarray, torch.Tensor, wp.array]

Example:

>>> # get DOF limits. Returned shape is (5, 9, 2) for the example: 5 envs, 9 DOFs
>>> prims.get_dof_limits()
[[[-2.8973  2.8973]
 [-1.7628  1.7628]
 [-2.8973  2.8973]
 [-3.0718 -0.0698]
 [-2.8973  2.8973]
 [-0.0175  3.7525]
 [-2.8973  2.8973]
 [ 0.      0.04  ]
 [ 0.      0.04  ]]
...
[[-2.8973  2.8973]
 [-1.7628  1.7628]
 [-2.8973  2.8973]
 [-3.0718 -0.0698]
 [-2.8973  2.8973]
 [-0.0175  3.7525]
 [-2.8973  2.8973]
 [ 0.      0.04  ]
 [ 0.      0.04  ]]]
get_dof_types(dof_names: Optional[List[str]] = None) List[str]

Get the DOF types given the DOF names

Parameters

dof_names (List[str], optional) – names of the joints that corresponds to the degrees of freedom to query. Defaults to None.

Returns

types of the joints that corresponds to the degrees of freedom. Types can be invalid, translation or rotation.

Return type

List[str]

Example:

>>> # get all DOF types
>>> prims.get_dof_types()
[<DofType.Rotation: 0>, <DofType.Rotation: 0>, <DofType.Rotation: 0>,
 <DofType.Rotation: 0>, <DofType.Rotation: 0>, <DofType.Rotation: 0>,
 <DofType.Rotation: 0>, <DofType.Translation: 1>, <DofType.Translation: 1>]
>>>
>>> # get only the finger DOF types: panda_finger_joint1 and panda_finger_joint2
>>> prims.get_dof_types(dof_names=["panda_finger_joint1", "panda_finger_joint2"])
[<DofType.Translation: 1>, <DofType.Translation: 1>]
get_drive_types() Union[numpy.ndarray, torch.Tensor]

Get the articulations DOFs limits (lower and upper)

Returns

degrees of freedom position limits. Shape is (N, num_dof). For the last dimension, index 0 corresponds to lower limits and index 1 corresponds to upper limits

Return type

Union[np.ndarray, torch.Tensor, wp.array]

get_effort_modes(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) List[str]

Get effort modes for articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Returns

Returns a List of size (M, K) indicating the effort modes: acceleration or force

Return type

List

Example:

>>> # get the effort mode for all joints
>>> prims.get_effort_modes()
[['acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration'],
 ['acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration'],
 ['acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration'],
 ['acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration'],
 ['acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration', 'acceleration']]
>>>
>>> # get only the finger joints effort modes for the first, middle and last of the 5 envs
>>> prims.get_effort_modes(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[['acceleration', 'acceleration'], ['acceleration', 'acceleration'], ['acceleration', 'acceleration']]
get_enabled_self_collisions(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the enable self collisions flag (physxArticulation:enabledSelfCollisions) for all articulations

Parameters

indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

self collisions flags (boolean interpreted as int). shape (M,)

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all self collisions flags. Returned shape is (5,) for the example: 5 envs
>>> prims.get_enabled_self_collisions()
[0 0 0 0 0]
>>>
>>> # get the self collisions flags for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_enabled_self_collisions(indices=np.array([0, 2, 4]))
[0 0 0]
get_fixed_tendon_dampings(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the dampings of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon dampings of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon dampings
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_dampings()
[[0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]]
get_fixed_tendon_limit_stiffnesses(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the limit stiffness of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon stiffnesses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon limit stiffnesses
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_limit_stiffnesses()
[[0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]]
get_fixed_tendon_limits(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the limits of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon stiffnesses of articulations in the view. Shape is (M, K, 2).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon limits
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_limits()
[[[-0.001  0.001] [-0.001  0.001] [-0.001  0.001] [-0.001  0.001]]
 [[-0.001  0.001] [-0.001  0.001] [-0.001  0.001] [-0.001  0.001]]
 [[-0.001  0.001] [-0.001  0.001] [-0.001  0.001] [-0.001  0.001]]
 [[-0.001  0.001] [-0.001  0.001] [-0.001  0.001] [-0.001  0.001]]
 [[-0.001  0.001] [-0.001  0.001] [-0.001  0.001] [-0.001  0.001]]]
get_fixed_tendon_offsets(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the offsets of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon stiffnesses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon offsets
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_offsets()
[[0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]]
get_fixed_tendon_rest_lengths(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the rest length of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon stiffnesses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon rest lengths
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_rest_lengths()
[[0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]]
get_fixed_tendon_stiffnesses(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the stiffness of fixed tendons for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

fixed tendon stiffnesses of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the fixed tendon stiffnesses
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> prims.get_fixed_tendon_stiffnesses()
[[0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]
 [0. 0. 0. 0.]]
get_friction_coefficients(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.array]

Get the friction coefficients for the articulation joints in the view

Search for “Joint Friction Coefficient” in PhysX docs for more details.

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (Optional[bool]) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint friction coefficients for articulations in the view. shape (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get joint friction coefficients. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_friction_coefficients()
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
>>>
>>> # get only the finger joint (panda_finger_joint1 (7) and panda_finger_joint2 (8)) friction coefficients
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_friction_coefficients(indices=np.array([0,2,4]), joint_indices=np.array([7,8]))
[[0. 0.]
 [0. 0.]
 [0. 0.]]
get_gains(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Tuple[typing.Union[numpy.ndarray, torch.Tensor], typing.Union[numpy.ndarray, torch.Tensor], typing.Union[warp.types.indexedarray, <Function index(a: vector(length=2, dtype=<class 'warp.types.float16'>), i: int32)>]]

Get the implicit Proportional-Derivative (PD) controller’s Kps (stiffnesses) and Kds (dampings) of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return clones of the internal buffers. Otherwise False. Defaults to True.

Returns

stiffness and damping of articulations in the view respectively. shapes are (M, K).

Return type

Tuple[Union[np.ndarray, torch.Tensor], Union[np.ndarray, torch.Tensor], Union[wp.indexedarray, wp.index]]

Example:

>>> # get all joint stiffness and damping. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> stiffnesses, dampings = prims.get_gains()
>>> stiffnesses
[[60000. 60000. 60000. 60000. 25000. 15000.  5000.  6000.  6000.]
 [60000. 60000. 60000. 60000. 25000. 15000.  5000.  6000.  6000.]
 [60000. 60000. 60000. 60000. 25000. 15000.  5000.  6000.  6000.]
 [60000. 60000. 60000. 60000. 25000. 15000.  5000.  6000.  6000.]
 [60000. 60000. 60000. 60000. 25000. 15000.  5000.  6000.  6000.]]
>>> dampings
[[3000. 3000. 3000. 3000. 3000. 3000. 3000. 1000. 1000.]
 [3000. 3000. 3000. 3000. 3000. 3000. 3000. 1000. 1000.]
 [3000. 3000. 3000. 3000. 3000. 3000. 3000. 1000. 1000.]
 [3000. 3000. 3000. 3000. 3000. 3000. 3000. 1000. 1000.]
 [3000. 3000. 3000. 3000. 3000. 3000. 3000. 1000. 1000.]]
>>>
>>> # get finger joints stiffness and damping: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> stiffnesses, dampings = prims.get_gains(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
>>> stiffnesses
[[6000. 6000.]
 [6000. 6000.]
 [6000. 6000.]]
>>> dampings
[[1000. 1000.]
 [1000. 1000.]
 [1000. 1000.]]
get_generalized_gravity_forces(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the generalized gravity forces (joint DOF forces required to counteract gravitational forces for the given articulation pose) of articulations in the view

Search for Generalized Gravity Force in PhysX docs for more details

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

generalized gravity forces of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>>

>>> # get all generalized gravity forces. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_generalized_gravity_forces()
[[ 1.32438602e-08 -6.90832138e+00 -1.08629465e-05  1.91585541e+01  5.13810664e-06
   1.18674076e+00  8.01788883e-06  5.18786255e-03 -5.18784765e-03]
 [ 1.32438602e-08 -6.90832138e+00 -1.08629465e-05  1.91585541e+01  5.13810664e-06
   1.18674076e+00  8.01788883e-06  5.18786255e-03 -5.18784765e-03]
 [ 1.32438585e-08 -6.90830994e+00 -1.08778477e-05  1.91585541e+01  5.14090061e-06
   1.18674052e+00  8.02161412e-06  5.18786255e-03 -5.18784765e-03]
 [ 1.32438585e-08 -6.90830994e+00 -1.08778477e-05  1.91585541e+01  5.14090061e-06
   1.18674052e+00  8.02161412e-06  5.18786255e-03 -5.18784765e-03]
 [ 1.32438602e-08 -6.90832138e+00 -1.08629465e-05  1.91585541e+01  5.13810664e-06
   1.18674076e+00  8.01788883e-06  5.18786255e-03 -5.18784765e-03]]
>>>
>>> # get finger joint generalized gravity forces: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_generalized_gravity_forces(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[ 0.00518786 -0.00518785]
 [ 0.00518786 -0.00518785]
 [ 0.00518786 -0.00518785]]
get_jacobian_shape() Union[numpy.ndarray, torch.Tensor, warp.types.array]

Get the Jacobian matrix shape of a single articulation

The Jacobian matrix maps the joint space velocities of a DOF to it’s cartesian and angular velocities

The shape of the Jacobian depends on the number of links (rigid bodies), DOFs, and whether the articulation base is fixed (e.g., robotic manipulators) or not (e.g,. mobile robots).

  • Fixed articulation base: (num_bodies - 1, 6, num_dof)

  • Non-fixed articulation base: (num_bodies, 6, num_dof + 6)

Each body has 6 values in the Jacobian representing its linear and angular motion along the three coordinate axes. The extra 6 DOFs in the last dimension, for non-fixed base cases, correspond to the linear and angular degrees of freedom of the free root link

Returns

shape of jacobian for a single articulation.

Return type

Union[np.ndarray, torch.Tensor, wp.array]

Example:

>>> # for the Franka Panda (a robotic manipulator with fixed base):
>>> # - num_bodies: 12
>>> # - num_dof: 9
>>> prims.get_jacobian_shape()
(11, 6, 9)
get_jacobians(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the Jacobian matrices of articulations in the view

Note

The first dimension corresponds to the amount of wrapped articulations while the last 3 dimensions are the Jacobian matrix shape. Refer to the get_jacobian_shape method for details about the Jacobian matrix shape

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

Jacobian matrices of articulations in the view. Shape is (M, jacobian_shape).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the Jacobian matrices. Returned shape is (5, 11, 6, 9) for the example: 5 envs, 12 links, 9 DOFs
>>> prims.get_jacobians()
[[[[ 4.2254178e-09  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]
   [ 1.2093576e-08  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]
   [-6.0873992e-16  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]
   [ 1.4458647e-07  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]
   [-1.8178657e-10  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]
   [ 9.9999976e-01  0.0000000e+00  0.0000000e+00 ...  0.0000000e+00  0.0000000e+00  0.0000000e+00]]
  ...
  [[-4.5089945e-02  8.1210062e-02 -3.8495898e-02 ...  2.8108317e-02  0.0000000e+00 -4.9317405e-02]
   [ 4.2863289e-01  9.7436900e-04  4.0475106e-01 ...  2.4577195e-03  0.0000000e+00  9.9807423e-01]
   [ 6.5973169e-09 -4.2914307e-01 -2.1542320e-02 ...  2.8352857e-02  0.0000000e+00 -3.7625343e-02]
   [ 1.4458647e-07 -1.1999309e-02 -5.3927803e-01 ...  7.0976764e-01  0.0000000e+00  0.0000000e+00]
   [-1.8178657e-10  9.9992776e-01 -6.4710006e-03 ...  8.5178167e-03  0.0000000e+00  0.0000000e+00]
   [ 9.9999976e-01 -3.8743019e-07  8.4210289e-01 ... -7.0438433e-01  0.0000000e+00  0.0000000e+00]]]]
get_joint_index(joint_name: str) int

Get a joint index in the joint buffers given its name

Parameters

joint_name (str) – name of the joint that corresponds to the index of the joint in the articulation

Returns

index of the joint in the joint buffers

Return type

int

get_joint_max_velocities(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the maximum joint velocities for articulation dofs in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (Optional[bool]) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

maximum joint velocities for articulations dofs in the view. shape (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

get_joint_positions(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the joint positions of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint positions of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all joint positions. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_joint_positions()
[[ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3220056e-08 -2.8105433e+00  6.8276104e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3220056e-08 -2.8105433e+00  6.8276104e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]]
>>>
>>> # get finger joint positions: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_joint_positions(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[0.03991237 0.04      ]
 [0.03991237 0.04      ]
 [0.03991237 0.04      ]]
get_joint_velocities(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the joint velocities of articulations in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint velocities of articulations in the view. Shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all joint velocities. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_joint_velocities()
[[ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]
 [ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]
 [ 1.9010074e-06 -7.6763779e-03 -2.1403629e-07  1.1063648e-02 -4.6333400e-05
   3.4824558e-02  8.8469170e-02  5.4033566e-04  1.0287110e-05]
 [ 1.9010074e-06 -7.6763779e-03 -2.1403629e-07  1.1063648e-02 -4.6333400e-05
   3.4824558e-02  8.8469170e-02  5.4033566e-04  1.0287110e-05]
 [ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]]
>>>
>>> # get finger joint velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_joint_velocities(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[5.4033857e-04 1.0287426e-05]
 [5.4033566e-04 1.0287110e-05]
 [5.4033857e-04 1.0287426e-05]]
get_joints_default_state() omni.isaac.core.utils.types.JointsState

Get the default joint states defined with the set_joints_default_state method

Returns

an object that contains the default joint states

Return type

JointsState

Example:

>>> # returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> states = prims.get_joints_default_state()
>>> states
<omni.isaac.core.utils.types.JointsState object at 0x7fc2c174fd90>
>>> states.positions
[[ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]
 [ 0.   -1.    0.   -2.2   0.    2.4   0.8   0.04  0.04]]
>>> states.velocities
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
>>> states.efforts
[[0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0. 0. 0. 0.]]
get_joints_state() omni.isaac.core.utils.types.JointsState

Get the current joint states (positions and velocities)

Returns

an object that contains the current joint positions and velocities

Return type

JointsState

Example:

>>> # returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> states = prims.get_joints_state()
>>> states
<omni.isaac.core.utils.types.JointsState object at 0x7fc1a23a82e0>
>>> states.positions
[[ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3220056e-08 -2.8105433e+00  6.8276104e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3220056e-08 -2.8105433e+00  6.8276104e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]
 [ 1.1999921e-02 -5.6962633e-01  1.3219320e-08 -2.8105433e+00  6.8276213e-06
   3.0301569e+00  7.3234755e-01  3.9912373e-02  3.9999999e-02]]
>>> states.velocities
[[ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]
 [ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]
 [ 1.9010074e-06 -7.6763779e-03 -2.1403629e-07  1.1063648e-02 -4.6333400e-05
   3.4824558e-02  8.8469170e-02  5.4033566e-04  1.0287110e-05]
 [ 1.9010074e-06 -7.6763779e-03 -2.1403629e-07  1.1063648e-02 -4.6333400e-05
   3.4824558e-02  8.8469170e-02  5.4033566e-04  1.0287110e-05]
 [ 1.9010375e-06 -7.6763844e-03 -2.1396865e-07  1.1063669e-02 -4.6333633e-05
   3.4824573e-02  8.8469200e-02  5.4033857e-04  1.0287426e-05]]
get_linear_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone=True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the linear velocities of prims in the view.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view)

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

linear velocities of the prims in the view. shape is (M, 3).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all articulation linear velocities. Returned shape is (5, 3) for the example: 5 envs, linear (3)
>>> prims.get_linear_velocities()
[[0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]]
>>>
>>> # get only the articulation linear velocities for the first, middle and last of the 5 envs.
>>> # Returned shape is (3, 3) for the example: 3 envs selected, linear (3)
>>> prims.get_linear_velocities(indices=np.array([0, 2, 4]))
[[0. 0. 0.]
 [0. 0. 0.]
 [0. 0. 0.]]

Get a link index in the link buffers given its name

Parameters

link_name (str) – name of the link that corresponds to the index of the link in the articulation

Returns

index of the link in the link buffers

Return type

int

get_local_poses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[Tuple[numpy.ndarray, numpy.ndarray], Tuple[torch.Tensor, torch.Tensor], Tuple[warp.types.indexedarray, warp.types.indexedarray]]

Get prim poses in the view with respect to the local frame (the prim’s parent frame).

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view)

Returns

first index is positions in the local frame of the prims. shape is (M, 3). Second index is quaternion orientations in the local frame of the prims. Quaternion is scalar-first (w, x, y, z). shape is (M, 4).

Return type

Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor], Tuple[wp.indexedarray, wp.indexedarray]]

Example:

>>> # get all articulation poses with respect to the local frame.
>>> # Returned shape is position (5, 3) and orientation (5, 4) for the example: 5 envs
>>> positions, orientations = prims.get_local_poses()
>>> positions
[[ 0.0000000e+00  0.0000000e+00 -2.8610229e-08]
 [ 0.0000000e+00  0.0000000e+00 -2.8610229e-08]
 [-4.5299529e-08  0.0000000e+00 -2.8610229e-08]
 [-4.5299529e-08  0.0000000e+00 -2.8610229e-08]
 [ 0.0000000e+00  0.0000000e+00 -2.8610229e-08]]
>>> orientations
[[1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]]
>>>
>>> # get only the articulation poses with respect to the local frame for the first, middle and last of the 5 envs.
>>> # Returned shape is position (3, 3) and orientation (3, 4) for the example: 3 envs selected
>>> positions, orientations = prims.get_local_poses(indices=np.array([0, 2, 4]))
>>> positions
[[ 0.0000000e+00  0.0000000e+00 -2.8610229e-08]
 [-4.5299529e-08  0.0000000e+00 -2.8610229e-08]
 [ 0.0000000e+00  0.0000000e+00 -2.8610229e-08]]
>>> orientations
[[1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]]
get_local_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get prim scales in the view with respect to the local frame (the parent’s frame).

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

scales applied to the prim’s dimensions in the local frame. shape is (M, 3).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all prims scales with respect to the local frame.
>>> # Returned shape is (5, 3) for the example: 5 envs
>>> prims.get_local_scales()
[[1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]]
>>>
>>> # get only the prims scales with respect to the local frame for the first, middle and last of the 5 envs.
>>> # Returned shape is (3, 3) for the example: 3 envs selected
>>> prims.get_local_scales(indices=np.array([0, 2, 4]))
[[1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]]
get_mass_matrices(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the mass matrices of articulations in the view

Note

The first dimension corresponds to the amount of wrapped articulations while the last 2 dimensions are the mass matrix shape. Refer to the get_mass_matrix_shape method for details about the mass matrix shape

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

mass matrices of articulations in the view. Shape is (M, mass_matrix_shape).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get the mass matrices. Returned shape is (5, 9, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_mass_matrices()
[[[ 5.0900602e-01  1.1794259e-06  4.2570841e-01 -1.6387942e-06 -3.1573933e-02
   -1.9736715e-06 -3.1358242e-04 -6.0441834e-03  6.0441834e-03]
  [ 1.1794259e-06  1.0598221e+00  7.4729815e-07 -4.2621672e-01  2.3612277e-08
   -4.9647894e-02 -2.9080724e-07 -1.8432185e-04  1.8432130e-04]
  ...
  [-6.0441834e-03 -1.8432185e-04 -5.7159867e-03  4.0070520e-04  9.6930371e-04
    1.2324301e-04  2.5264668e-10  1.4055224e-02  0.0000000e+00]
  [ 6.0441834e-03  1.8432130e-04  5.7159867e-03 -4.0070404e-04 -9.6930366e-04
   -1.2324269e-04 -3.6906206e-10  0.0000000e+00  1.4055224e-02]]]
get_mass_matrix_shape() Union[numpy.ndarray, torch.Tensor, warp.types.array]

Get the mass matrix shape of a single articulation

The mass matrix contains the generalized mass of the robot depending on the current configuration

The shape of the max matrix depends on the number of DOFs: (num_dof, num_dof)

Returns

shape of mass matrix for a single articulation.

Return type

Union[np.ndarray, torch.Tensor, wp.array]

Example:

>>> # for the Franka Panda:
>>> # - num_dof: 9
>>> prims.get_jacobian_shape()
(9, 9)
get_max_efforts(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the maximum efforts for articulation in the view

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (Optional[bool]) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

maximum efforts for articulations in the view. shape (M, K).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all joint maximum efforts. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_max_efforts()
[[5220. 5220. 5220. 5220.  720.  720.  720.  720.  720.]
 [5220. 5220. 5220. 5220.  720.  720.  720.  720.  720.]
 [5220. 5220. 5220. 5220.  720.  720.  720.  720.  720.]
 [5220. 5220. 5220. 5220.  720.  720.  720.  720.  720.]
 [5220. 5220. 5220. 5220.  720.  720.  720.  720.  720.]]
>>>
>>> # get finger joint maximum efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_max_efforts(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[720. 720.]
 [720. 720.]
 [720. 720.]]
get_measured_joint_efforts(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Returns the efforts computed/measured by the physics solver of the joint forces in the DOF motion direction

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor]], optional) – joint indices to specify which joints to query. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

computed joint efforts of articulations in the view. shape is (M, K).

Return type

Union[np.ndarray, torch.Tensor]

Example:

>>> # get all measured joint efforts. Returned shape is (5, 9) for the example: 5 envs, 9 DOFs
>>> prims.get_measured_joint_efforts()
[[ 4.8250298e-05 -6.9073005e+00  5.3364405e-05  1.9157070e+01 -5.8759182e-05
   1.1863427e+00 -5.6388220e-05  5.1680300e-03 -5.1910817e-03]
 [ 4.8250298e-05 -6.9073005e+00  5.3364405e-05  1.9157070e+01 -5.8759182e-05
   1.1863427e+00 -5.6388220e-05  5.1680300e-03 -5.1910817e-03]
 [ 4.8254540e-05 -6.9072919e+00  5.3344327e-05  1.9157072e+01 -5.8761045e-05
   1.1863427e+00 -5.6405144e-05  5.1680212e-03 -5.1910840e-03]
 [ 4.8254540e-05 -6.9072919e+00  5.3344327e-05  1.9157072e+01 -5.8761045e-05
   1.1863427e+00 -5.6405144e-05  5.1680212e-03 -5.1910840e-03]
 [ 4.8250298e-05 -6.9073005e+00  5.3364405e-05  1.9157070e+01 -5.8759182e-05
   1.1863427e+00 -5.6388220e-05  5.1680300e-03  -5.1910817e-03]]
>>>
>>> # get finger measured joint efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs. Returned shape is (3, 2)
>>> prims.get_measured_joint_efforts(indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
[[ 0.00516803 -0.00519108]
 [ 0.00516802 -0.00519108]
 [ 0.00516803 -0.00519108]]
get_measured_joint_forces(indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Get the measured joint reaction forces and torques (link incoming joint forces and torques) to external loads

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.

prims._metadata.joint_names  # list of names
prims._metadata.joint_indices  # dict of name: index

To retrieve a specific row for the link incoming joint force/torque use joint_index + 1

Parameters
  • indices (Optional[Union[np.ndarray, List, torch.Tensor]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor]], optional) – link indices to specify which link’s incoming joints to query. Shape (K,). Where K <= num of links/bodies. Defaults to None (i.e: all dofs).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

joint forces and torques of articulations in the view. Shape is (M, num_joint + 1, 6). Column 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

Return type

Union[np.ndarray, torch.Tensor]

Example:

>>> # get all measured joint forces and torques. Returned shape is (5, 12, 6) for the example:
>>> # 5 envs, 9 DOFs (but 12 joints including the fixed and root joints)
>>> prims.get_measured_joint_forces()
[[[ 0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00]
  [ 1.49950760e+02  3.52353277e-06  5.62586996e-04  4.82502983e-05 -6.90729856e+00  2.69259126e-05]
  [-2.60467059e-05 -1.06778236e+02 -6.83844986e+01 -6.90730047e+00 -5.27759657e-05 -1.24897576e-06]
  [ 8.71209946e+01 -4.46646191e-05 -5.57951622e+01  5.33644052e-05 -2.45385647e+01  1.38957939e-05]
  [ 5.18576926e-05 -4.81099091e+01  6.07092705e+01  1.91570702e+01 -5.81023924e-05  1.46875891e-06]
  [-3.16910419e+01  2.31799815e-04  3.99901695e+01 -5.87591821e-05 -1.18634319e+00  2.24427877e-05]
  [-1.07621672e-04  1.53405371e+01 -1.54584875e+01  1.18634272e+00  6.09036942e-05 -1.60679410e-05]
  [-7.54189777e+00 -5.08146524e+00 -5.65130091e+00 -5.63882204e-05  3.88599992e-01 -3.49432468e-01]
  [ 4.74214745e+00 -3.19458222e+00  3.55281782e+00  5.58562024e-05  8.47946014e-03  7.64050474e-03]
  [ 4.07607269e+00  2.16406956e-01 -4.05131817e+00 -5.95658377e-04  1.14070829e-02  2.13965313e-06]
  [ 5.16803004e-03 -9.77545828e-02 -9.70939621e-02 -8.41282599e-12 -1.29066744e-12 -1.93477560e-11]
  [-5.19108167e-03  9.75882635e-02 -9.71064270e-02  8.41282859e-12  1.29066018e-12 -1.93477543e-11]]
 ...
 [[ 0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00  0.00000000e+00]
  [ 1.49950760e+02  3.52353277e-06  5.62586996e-04  4.82502983e-05 -6.90729856e+00  2.69259126e-05]
  [-2.60467059e-05 -1.06778236e+02 -6.83844986e+01 -6.90730047e+00 -5.27759657e-05 -1.24897576e-06]
  [ 8.71209946e+01 -4.46646191e-05 -5.57951622e+01  5.33644052e-05 -2.45385647e+01  1.38957939e-05]
  [ 5.18576926e-05 -4.81099091e+01  6.07092705e+01  1.91570702e+01 -5.81023924e-05  1.46875891e-06]
  [-3.16910419e+01  2.31799815e-04  3.99901695e+01 -5.87591821e-05 -1.18634319e+00  2.24427877e-05]
  [-1.07621672e-04  1.53405371e+01 -1.54584875e+01  1.18634272e+00  6.09036942e-05 -1.60679410e-05]
  [-7.54189777e+00 -5.08146524e+00 -5.65130091e+00 -5.63882204e-05  3.88599992e-01 -3.49432468e-01]
  [ 4.74214745e+00 -3.19458222e+00  3.55281782e+00  5.58562024e-05  8.47946014e-03  7.64050474e-03]
  [ 4.07607269e+00  2.16406956e-01 -4.05131817e+00 -5.95658377e-04  1.14070829e-02  2.13965313e-06]
  [ 5.16803004e-03 -9.77545828e-02 -9.70939621e-02 -8.41282599e-12 -1.29066744e-12 -1.93477560e-11]
  [-5.19108167e-03  9.75882635e-02 -9.71064270e-02  8.41282859e-12  1.29066018e-12 -1.93477543e-11]]]
>>>
>>> # get measured joint forces and torques for the fingers for the first, middle and last of the 5 envs.
>>> # Returned shape is (3, 2, 6)
>>> metadata = prims._metadata
>>> joint_indices = 1 + np.array([
>>>     metadata.joint_indices["panda_finger_joint1"],
>>>     metadata.joint_indices["panda_finger_joint2"],
>>> ])
>>> joint_indices
[10 11]
>>> prims.get_measured_joint_forces(indices=np.array([0, 2, 4]), joint_indices=joint_indices)
[[[ 5.1680300e-03 -9.7754583e-02 -9.7093962e-02 -8.4128260e-12 -1.2906674e-12 -1.9347756e-11]
  [-5.1910817e-03  9.7588263e-02 -9.7106427e-02  8.4128286e-12  1.2906602e-12 -1.9347754e-11]]
 [[ 5.1680212e-03 -9.7754560e-02 -9.7093947e-02 -8.4141834e-12 -1.2907383e-12 -1.9348209e-11]
  [-5.1910840e-03  9.7588278e-02 -9.7106412e-02  8.4141869e-12  1.2907335e-12 -1.9348207e-11]]
 [[ 5.1680300e-03 -9.7754583e-02 -9.7093962e-02 -8.4128260e-12 -1.2906674e-12 -1.9347756e-11]
  [-5.1910817e-03  9.7588263e-02 -9.7106427e-02  8.4128286e-12  1.2906602e-12 -1.9347754e-11]]]
get_sleep_thresholds(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the threshold for articulations to enter a sleep state

Search for Articulations and Sleeping in PhysX docs for more details

Parameters

indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

sleep thresholds. shape (M,).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all sleep thresholds. Returned shape is (5,) for the example: 5 envs
>>> prims.get_sleep_thresholds()
[0.005 0.005 0.005 0.005 0.005]
>>>
>>> # get the sleep thresholds for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_sleep_thresholds(indices=np.array([0, 2, 4]))
[0.005 0.005 0.005]
get_solver_position_iteration_counts(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the solver (position) iteration count for the articulations

The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.

Parameters

indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

position iteration count. Shape (M,).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all position iteration count. Returned shape is (5,) for the example: 5 envs
>>> prims.get_solver_position_iteration_counts()
[32 32 32 32 32]
>>>
>>> # get the position iteration count for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_solver_position_iteration_counts(indices=np.array([0, 2, 4]))
[32 32 32]
get_solver_velocity_iteration_counts(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the solver (velocity) iteration count for the articulations

The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.

Parameters

indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

velocity iteration count. Shape (M,).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all velocity iteration count. Returned shape is (5,) for the example: 5 envs
>>> prims.get_solver_velocity_iteration_counts()
[32 32 32 32 32]
>>>
>>> # get the velocity iteration count for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_solver_velocity_iteration_counts(indices=np.array([0, 2, 4]))
[32 32 32]
get_stabilization_thresholds(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the mass-normalized kinetic energy below which the articulations may participate in stabilization

Search for Stabilization Threshold in PhysX docs for more details

Parameters

indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

stabilization threshold. Shape (M,).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all stabilization thresholds. Returned shape is (5,) for the example: 5 envs
>>> prims.get_solver_velocity_iteration_counts()
[0.001 0.001 0.001 0.001 0.001]
>>>
>>> # get the stabilization thresholds for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_solver_velocity_iteration_counts(indices=np.array([0, 2, 4]))
[0.001 0.001 0.001]
get_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get the linear and angular velocities of prims in the view.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view)

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

linear and angular velocities of the prims in the view concatenated. shape is (M, 6). For the last dimension the first 3 values are for linear velocities and the last 3 for angular velocities

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all articulation velocities. Returned shape is (5, 6) for the example: 5 envs, linear (3) and angular (3)
>>> prims.get_velocities()
[[0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]]
>>>
>>> # get only the articulation velocities for the first, middle and last of the 5 envs.
>>> # Returned shape is (3, 6) for the example: 3 envs selected, linear (3) and angular (3)
>>> prims.get_velocities(indices=np.array([0, 2, 4]))
[[0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]
 [0. 0. 0. 0. 0. 0.]]
get_visibilities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Returns the current visibilities of the prims in stage.

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

Shape (M,) with type bool, where each item holds True

if the prim is visible in stage. False otherwise.

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all visibilities. Returned shape is (5,) for the example: 5 envs
>>> prims.get_visibilities()
[ True  True  True  True  True]
>>>
>>> # get the visibilities for the first, middle and last of the 5 envs. Returned shape is (3,)
>>> prims.get_visibilities(indices=np.array([0, 2, 4]))
[ True  True  True]
get_world_poses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True, usd: bool = True) Union[Tuple[numpy.ndarray, numpy.ndarray], Tuple[torch.Tensor, torch.Tensor], Tuple[warp.types.indexedarray, warp.types.indexedarray]]

Get the poses of the prims in the view with respect to the world’s frame.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

  • usd (bool, optional) – True to query from usd. Otherwise False to query from Fabric data. Defaults to True.

Returns

first index is positions in the world frame of the prims. shape is (M, 3). Second index is quaternion orientations in the world frame of the prims. Quaternion is scalar-first (w, x, y, z). shape is (M, 4).

Return type

Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor], Tuple[wp.indexedarray, wp.indexedarray]]

Example:

>>> # get all articulation poses with respect to the world's frame.
>>> # Returned shape is position (5, 3) and orientation (5, 4) for the example: 5 envs
>>> positions, orientations = prims.get_world_poses()
>>> positions
[[ 1.5000000e+00 -7.5000000e-01 -2.8610229e-08]
 [ 1.5000000e+00  7.5000000e-01 -2.8610229e-08]
 [-4.5299529e-08 -7.5000000e-01 -2.8610229e-08]
 [-4.5299529e-08  7.5000000e-01 -2.8610229e-08]
 [-1.5000000e+00 -7.5000000e-01 -2.8610229e-08]]
>>> orientations
[[1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]]
>>>
>>> # get only the articulation poses with respect to the world's frame for the first, middle and last of the 5 envs.
>>> # Returned shape is position (3, 3) and orientation (3, 4) for the example: 3 envs selected
>>> positions, orientations = prims.get_world_poses(indices=np.array([0, 2, 4]))
>>> positions
[[ 1.5000000e+00 -7.5000000e-01 -2.8610229e-08]
 [-4.5299529e-08 -7.5000000e-01 -2.8610229e-08]
 [-1.5000000e+00 -7.5000000e-01 -2.8610229e-08]]
>>> orientations
[[1. 0. 0. 0.]
 [1. 0. 0. 0.]
 [1. 0. 0. 0.]]
get_world_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]

Get prim scales in the view with respect to the world’s frame

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

scales applied to the prim’s dimensions in the world frame. shape is (M, 3).

Return type

Union[np.ndarray, torch.Tensor, wp.indexedarray]

Example:

>>> # get all prims scales with respect to the world's frame.
>>> # Returned shape is (5, 3) for the example: 5 envs
>>> prims.get_world_scales()
[[1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]]
>>>
>>> # get only the prims scales with respect to the world's frame for the first, middle and last of the 5 envs.
>>> # Returned shape is (3, 3) for the example: 3 envs selected
>>> prims.get_world_scales(indices=np.array([0, 2, 4]))
[[1. 1. 1.]
 [1. 1. 1.]
 [1. 1. 1.]]
initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None

Create a physics simulation view if not passed and set other properties using the PhysX tensor API

Note

If the articulation view has been added to the world scene (e.g., world.scene.add(prims)), it will be automatically initialized when the world is reset (e.g., world.reset()).

Warning

This method needs to be called after each hard reset (e.g., Stop + Play on the timeline) before interacting with any other class method.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

Example:

>>> prims.initialize()
property initialized: bool

Check if articulation view is initialized

Returns

True if the view object was initialized (after the first call of .initialize()). False otherwise.

Return type

bool

Example:

>>> # given an initialized articulation view
>>> prims.initialized
True

Returns: bool: True if the prim corresponds to a non root link in an articulation. Otherwise False.

is_physics_handle_valid() bool

Check if articulation view’s physics handler is initialized

Warning

If the physics handler is not valid many of the methods that requires PhysX will return None.

Returns

False if .initialize() needs to be called again for the physics handle to be valid. Otherwise True

Return type

bool

Example:

>>> prims.is_physics_handle_valid()
True
is_valid(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) bool

Check that all prims have a valid USD Prim

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

True if all prim paths specified in the view correspond to a valid prim in stage. False otherwise.

Return type

bool

Example:

>>> prims.is_valid()
True
is_visual_material_applied(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) List[bool]

Check if there is a visual material applied

Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

True if there is a visual material applied is applied to the corresponding prim in the view. False otherwise.

Return type

List[bool]

Example:

>>> # given a visual material that is applied only to the first and the last environment
>>> prims.is_visual_material_applied()
[True, False, False, False, True]
>>>
>>> # check for the first, middle and last of the 5 envs
>>> prims.is_visual_material_applied(indices=np.array([0, 2, 4]))
[True, False, True]
property joint_names: List[str]

List of prim names for each joint of the articulations

Returns

ordered names of joints that corresponds to degrees of freedom for the articulations in the view

Return type

List[str]

property name: str

Returns: str: name given to the prims view when instantiating it.

property num_bodies: int

Number of rigid bodies (links) of the articulations

Returns

maximum number of rigid bodies for the articulations in the view

Return type

int

Example:

>>> prims.num_bodies
12
property num_dof: int

Number of DOF of the articulations

Returns

maximum number of DOFs for the articulations in the view

Return type

int

Example:

>>> prims.num_dof
9
property num_fixed_tendons: int

Number of fixed tendons of the articulations

Returns

maximum number of fixed tendons for the articulations in the view

Return type

int

Example:

>>> prims.num_fixed_tendons
0
property num_joints: int

Number of joints of the articulations

Returns

number of joints of the articulations in the view

Return type

int

property num_shapes: int

Number of rigid shapes of the articulations

Returns

maximum number of rigid shapes for the articulations in the view

Return type

int

Example:

>>> prims.num_shapes
17
pause_motion() None

Pauses the motion of all articulations wrapped under the ArticulationView.

post_reset() None

Reset the articulations to their default states

Note

For the articulations, in addition to configuring the root prim’s default positions and spatial orientations (defined via the set_default_state method), the joint’s positions, velocities, and efforts (defined via the set_joints_default_state method) and the joint stiffnesses and dampings (defined via the set_gains method) are imposed

Example:

>>> prims.post_reset()
property prim_paths: List[str]
Returns

list of prim paths in the stage encapsulated in this view.

Return type

List[str]

Example:

>>> prims.prim_paths
['/World/envs/env_0', '/World/envs/env_1', '/World/envs/env_2', '/World/envs/env_3', '/World/envs/env_4']
property prims: List[pxr.Usd.Prim]
Returns

List of USD Prim objects encapsulated in this view.

Return type

List[Usd.Prim]

Example:

>>> prims.prims
[Usd.Prim(</World/envs/env_0>), Usd.Prim(</World/envs/env_1>), Usd.Prim(</World/envs/env_2>),
 Usd.Prim(</World/envs/env_3>), Usd.Prim(</World/envs/env_4>)]
resume_motion()

Resumes the motion of all articulations wrapped under the ArticulationView using the position and velocity dof targets cached when pause_motion was called.

set_angular_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set the angular velocities of the prims in the view

The method does this through the physx API only. It has to be called after initialization. Note: This method is not supported for the gpu pipeline. set_velocities method should be used instead.

Warning

This method will immediately set the articulation state

Parameters
  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – angular velocities to set the rigid prims to. shape is (M, 3).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Hint

This method belongs to the methods used to set the articulation kinematic state:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set each articulation linear velocity to (0.1, 0.1, 0.1)
>>> velocities = np.full((num_envs, 3), fill_value=0.1)
>>> prims.set_angular_velocities(velocities)
>>>
>>> # set only the articulation linear velocities for the first, middle and last of the 5 envs
>>> velocities = np.full((3, 3), fill_value=0.1)
>>> prims.set_angular_velocities(velocities, indices=np.array([0, 2, 4]))
set_armatures(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set armatures for articulation joints in the view

Search for “Joint Armature” in PhysX docs for more details.

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – armatures for articulation joints in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Example:

>>> # set all joint armatures to 0.05 for all envs
>>> prims.set_armatures(np.full((num_envs, prims.num_dof), 0.05))
>>>
>>> # set only the finger joint (panda_finger_joint1 (7) and panda_finger_joint2 (8)) armatures
>>> # for the first, middle and last of the 5 envs to 0.05
>>> prims.set_armatures(np.full((3, 2), 0.05), indices=np.array([0,2,4]), joint_indices=np.array([7,8]))
set_body_coms(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set body center of mass (COM) positions and orientations for articulation bodies in the view.

Parameters
  • positions (Union[np.ndarray, torch.Tensor, wp.array]) – body center of mass positions for articulations in the view. shape (M, K, 3).

  • orientations (Union[np.ndarray, torch.Tensor, wp.array]) – body center of mass orientations for articulations in the view. shape (M, K, 4).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to manipulate. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

Example:

>>> # set the center of mass for all the articulation rigid bodies to the indicated values.
>>> # Since there are 5 envs, the inertias are repeated 5 times
>>> positions = np.tile(np.array([0.01, 0.02, 0.03]), (num_envs, prims.num_bodies, 1))
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (num_envs, prims.num_bodies, 1))
>>> prims.set_body_coms(positions, orientations)
>>>
>>> # set the fingers center of mass: panda_leftfinger (10) and panda_rightfinger (11) to 0.2
>>> # for the first, middle and last of the 5 envs
>>> positions = np.tile(np.array([0.01, 0.02, 0.03]), (3, 2, 1))
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (3, 2, 1))
>>> prims.set_body_coms(positions, orientations, indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
set_body_disable_gravity(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set body gravity activation articulation bodies in the view.

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – body gravity activation for articulations in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to manipulate. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

set_body_inertias(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set body inertias for articulation bodies in the view.

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – body inertias for articulations in the view. shape (M, K, 9).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to manipulate. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

Example:

>>> # set the inertias for all the articulation rigid bodies to the indicated values.
>>> # Since there are 5 envs, the inertias are repeated 5 times
>>> inertias = np.tile(np.array([0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]), (num_envs, prims.num_bodies, 1))
>>> prims.set_body_inertias(inertias)
>>>
>>> # set the fingers inertias: panda_leftfinger (10) and panda_rightfinger (11) to 0.2
>>> # for the first, middle and last of the 5 envs
>>> inertias = np.tile(np.array([0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]), (3, 2, 1))
>>> prims.set_body_inertias(inertias, indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
set_body_masses(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, body_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set body masses for articulation bodies in the view

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – body masses for articulations in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • body_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – body indices to specify which bodies to manipulate. Shape (K,). Where K <= num of bodies. Defaults to None (i.e: all bodies).

Example:

>>> # set the masses for all the articulation rigid bodies to the indicated values.
>>> # Since there are 5 envs, the masses are repeated 5 times
>>> masses = np.tile(np.array([1.2, 1.1, 1.0, 0.9, 0.8, 0.7, 0.6, 0.5, 0.4, 0.3, 0.2, 0.2]), (num_envs, 1))
>>> prims.set_body_masses(masses)
>>>
>>> # set the fingers masses: panda_leftfinger (10) and panda_rightfinger (11) to 0.2
>>> # for the first, middle and last of the 5 envs
>>> masses = np.tile(np.array([0.2, 0.2]), (3, 1))
>>> prims.set_body_masses(masses, indices=np.array([0, 2, 4]), body_indices=np.array([10, 11]))
set_default_state(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set the default state of the prims (positions and orientations), that will be used after each reset.

Note

The default states will be set during post-reset (e.g., calling .post_reset() or world.reset() methods)

Parameters
  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – positions in the world frame of the prim. shape is (M, 3). Defaults to None, which means left unchanged.

  • orientations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – quaternion orientations in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (M, 4). Defaults to None, which means left unchanged.

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # configure default states for all prims
>>> positions = np.zeros((num_envs, 3))
>>> positions[:, 0] = np.arange(num_envs)
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (num_envs, 1))
>>> prims.set_default_state(positions=positions, orientations=orientations)
>>>
>>> # set default states during post-reset
>>> prims.post_reset()
set_effort_modes(mode: str, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None

Set effort modes for articulations in the view

Parameters
  • mode (str) – effort mode to be applied to prims in the view: acceleration or force.

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Example:

>>> # set the effort mode for all joints to 'force'
>>> prims.set_effort_modes("force")
>>>
>>> # set only the finger joints effort mode to 'force' for the first, middle and last of the 5 envs
>>> prims.set_effort_modes("force", indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_enabled_self_collisions(flags: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the enable self collisions flag (physxArticulation:enabledSelfCollisions)

Parameters
  • flags (Union[np.ndarray, torch.Tensor, wp.array]) – true to enable self collision. otherwise false. shape (M,)

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # enable the self collisions flag for all envs
>>> prims.set_enabled_self_collisions(np.full((num_envs,), True))
>>>
>>> # enable the self collisions flag only for the first, middle and last of the 5 envs
>>> prims.set_enabled_self_collisions(np.full((3,), True), indices=np.array([0, 2, 4]))
set_fixed_tendon_properties(stiffnesses: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, dampings: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, limit_stiffnesses: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, limits: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, rest_lengths: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, offsets: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set fixed tendon properties for articulations in the view

Search for Fixed Tendon in PhysX docs for more details

Parameters
  • stiffnesses (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon stiffnesses for articulations in the view. shape (M, K).

  • dampings (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon dampings for articulations in the view. shape (M, K).

  • limit_stiffnesses (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon limit stiffnesses for articulations in the view. shape (M, K).

  • limits (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon limits for articulations in the view. shape (M, K, 2).

  • rest_lengths (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon rest lengths for articulations in the view. shape (M, K).

  • offsets (Union[np.ndarray, torch.Tensor, wp.array]) – fixed tendon offsets for articulations in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the limit stiffnesses and dampings
>>> # for the ShadowHand articulation that has 4 fixed tendons (prims.num_fixed_tendons)
>>> limit_stiffnesses = np.full((num_envs, prims.num_fixed_tendons), fill_value=10.0)
>>> dampings = np.full((num_envs, prims.num_fixed_tendons), fill_value=0.1)
>>> prims.set_fixed_tendon_properties(dampings=dampings, limit_stiffnesses=limit_stiffnesses)
set_friction_coefficients(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the friction coefficients for articulation joints in the view

Search for “Joint Friction Coefficient” in PhysX docs for more details.

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – friction coefficients for articulation joints in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Example:

>>> # set all joint friction coefficients to 0.05 for all envs
>>> prims.set_friction_coefficients(np.full((num_envs, prims.num_dof), 0.05))
>>>
>>> # set only the finger joint (panda_finger_joint1 (7) and panda_finger_joint2 (8)) friction coefficients
>>> # for the first, middle and last of the 5 envs to 0.05
>>> prims.set_friction_coefficients(np.full((3, 2), 0.05), indices=np.array([0,2,4]), joint_indices=np.array([7,8]))
set_gains(kps: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, kds: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, save_to_usd: bool = False) None

Set the implicit Proportional-Derivative (PD) controller’s Kps (stiffnesses) and Kds (dampings) of articulations in the view

Parameters
  • kps (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – stiffness of the drives. shape is (M, K). Defaults to None.

  • kds (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – damping of the drives. shape is (M, K).. Defaults to None.

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

  • save_to_usd (bool, optional) – True to save the gains in the usd. otherwise False.

Example:

>>> # set the gains (stiffnesses and dampings) for all the articulation joints to the indicated values.
>>> # Since there are 5 envs, the gains are repeated 5 times
>>> stiffnesses = np.tile(np.array([100000, 100000, 100000, 100000, 80000, 80000, 80000, 50000, 50000]), (num_envs, 1))
>>> dampings = np.tile(np.array([8000, 8000, 8000, 8000, 5000, 5000, 5000, 2000, 2000]), (num_envs, 1))
>>> prims.set_gains(kps=stiffnesses, kds=dampings)
>>>
>>> # set the fingers gains (stiffnesses and dampings): panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # to 50000 and 2000 respectively for the first, middle and last of the 5 envs
>>> stiffnesses = np.tile(np.array([50000, 50000]), (3, 1))
>>> dampings = np.tile(np.array([2000, 2000]), (3, 1))
>>> prims.set_gains(kps=stiffnesses, kds=dampings, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joint_efforts(efforts: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the joint efforts of articulations in the view

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 (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – efforts of articulations in the view to be set to in the next frame. shape is (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Hint

This method belongs to the methods used to set the articulation kinematic states:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set the efforts for all the articulation joints to the indicated values.
>>> # Since there are 5 envs, the joint efforts are repeated 5 times
>>> efforts = np.tile(np.array([10, 20, 30, 40, 50, 60, 70, 80, 90]), (num_envs, 1))
>>> prims.set_joint_efforts(efforts)
>>>
>>> # set the fingers efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 10
>>> # for the first, middle and last of the 5 envs
>>> efforts = np.tile(np.array([10, 10]), (3, 1))
>>> prims.set_joint_efforts(efforts, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joint_position_targets(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the joint position targets for the implicit Proportional-Derivative (PD) controllers

Note

This is an independent method for controlling joints. To apply multiple targets (position, velocity, and/or effort) in the same call, consider using the apply_action method

Parameters
  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – joint position targets for the implicit PD controller. shape is (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

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)

Example:

>>> # apply the target positions (to move all the robot joints) to the indicated values.
>>> # Since there are 5 envs, the joint positions are repeated 5 times
>>> positions = np.tile(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), (num_envs, 1))
>>> prims.set_joint_position_targets(positions)
>>>
>>> # close the robot fingers: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0
>>> # for the first, middle and last of the 5 envs
>>> positions = np.tile(np.array([0.0, 0.0]), (3, 1))
>>> prims.set_joint_position_targets(positions, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joint_positions(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the joint positions of articulations in the view

Warning

This method will immediately set (teleport) the affected joints to the indicated value. Use the set_joint_position_targets or the apply_action methods to control the articulation joints.

Parameters
  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – joint positions of articulations in the view to be set to in the next frame. shape is (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Hint

This method belongs to the methods used to set the articulation kinematic states:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set all the articulation joints.
>>> # Since there are 5 envs, the joint positions are repeated 5 times
>>> positions = np.tile(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), (num_envs, 1))
>>> prims.set_joint_positions(positions)
>>>
>>> # set only the fingers in closed position: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0
>>> # for the first, middle and last of the 5 envs
>>> positions = np.tile(np.array([0.0, 0.0]), (3, 1))
>>> prims.set_joint_positions(positions, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joint_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the joint velocities of articulations in the view

Warning

This method will immediately set the affected joints to the indicated value. Use the set_joint_velocity_targets or the apply_action methods to control the articulation joints.

Parameters
  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – joint velocities of articulations in the view to be set to in the next frame. shape is (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Hint

This method belongs to the methods used to set the articulation kinematic states:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set the velocities for all the articulation joints to the indicated values.
>>> # Since there are 5 envs, the joint velocities are repeated 5 times
>>> velocities = np.tile(np.array([0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9]), (num_envs, 1))
>>> prims.set_joint_velocities(velocities)
>>>
>>> # set the fingers velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) to -0.1
>>> # for the first, middle and last of the 5 envs
>>> velocities = np.tile(np.array([-0.1, -0.1]), (3, 1))
>>> prims.set_joint_velocities(velocities, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joint_velocity_targets(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the joint velocity targets for the implicit Proportional-Derivative (PD) controllers

Note

This is an independent method for controlling joints. To apply multiple targets (position, velocity, and/or effort) in the same call, consider using the apply_action method

Parameters
  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – joint velocity targets for the implicit PD controller. shape is (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

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 velocity control, stiffness must be set to zero with a non-zero damping

Example:

>>> # apply the target velocities for all the articulation joints to the indicated values.
>>> # Since there are 5 envs, the joint velocities are repeated 5 times
>>> velocities = np.tile(np.array([0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9]), (num_envs, 1))
>>> prims.set_joint_velocity_targets(velocities)
>>>
>>> # apply the fingers target velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) to -1.0
>>> # for the first, middle and last of the 5 envs
>>> velocities = np.tile(np.array([-0.1, -0.1]), (3, 1))
>>> prims.set_joint_velocity_targets(velocities, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_joints_default_state(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, efforts: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None) None

Set the joints default state (joint positions, velocities and efforts) to be applied after each reset.

Note

The default states will be set during post-reset (e.g., calling .post_reset() or world.reset() methods)

Parameters
  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default joint positions. shape is (N, num of dofs). Defaults to None.

  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default joint velocities. shape is (N, num of dofs). Defaults to None.

  • efforts (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default joint efforts. shape is (N, num of dofs). Defaults to None.

Example:

>>> # configure default joint states for all articulations
>>> positions = np.tile(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), (num_envs, 1))
>>> prims.set_joints_default_state(
...     positions=positions,
...     velocities=np.zeros((num_envs, prims.num_dof)),
...     efforts=np.zeros((num_envs, prims.num_dof))
... )
>>>
>>> # set default states during post-reset
>>> prims.post_reset()
set_linear_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set the linear velocities of the prims in the view

The method does this through the PhysX API only. It has to be called after initialization. Note: This method is not supported for the gpu pipeline. set_velocities method should be used instead.

Warning

This method will immediately set the articulation state

Parameters
  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – linear velocities to set the rigid prims to. shape is (M, 3).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Hint

This method belongs to the methods used to set the articulation kinematic state:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set each articulation linear velocity to (1.0, 1.0, 1.0)
>>> velocities = np.ones((num_envs, 3))
>>> prims.set_linear_velocities(velocities)
>>>
>>> # set only the articulation linear velocities for the first, middle and last of the 5 envs
>>> velocities = np.ones((3, 3))
>>> prims.set_linear_velocities(velocities, indices=np.array([0, 2, 4]))
set_local_poses(translations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set prim poses in the view with respect to the local frame (the prim’s parent frame).

Warning

This method will change (teleport) the prim poses immediately to the indicated value

Parameters
  • translations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – translations in the local frame of the prims (with respect to its parent prim). shape is (M, 3). Defaults to None, which means left unchanged.

  • orientations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – quaternion orientations in the local frame of the prims. quaternion is scalar-first (w, x, y, z). shape is (M, 4). Defaults to None, which means left unchanged.

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Hint

This method belongs to the methods used to set the prim state

Example:

>>> # reposition all articulations
>>> positions = np.zeros((num_envs, 3))
>>> positions[:,0] = np.arange(num_envs)
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (num_envs, 1))
>>> prims.set_local_poses(positions, orientations)
>>>
>>> # reposition only the articulations for the first, middle and last of the 5 envs
>>> positions = np.zeros((3, 3))
>>> positions[:,1] = np.arange(3)
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (3, 1))
>>> prims.set_local_poses(positions, orientations, indices=np.array([0, 2, 4]))
set_local_scales(scales: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set prim scales in the view with respect to the local frame (the prim’s parent frame)

Parameters
  • scales (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – scales to be applied to the prim’s dimensions in the view. shape is (M, 3).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the scale for all prims. Since there are 5 envs, the scale is repeated 5 times
>>> scales = np.tile(np.array([1.0, 0.75, 0.5]), (num_envs, 1))
>>> prims.set_local_scales(scales)
>>>
>>> # set the scale for the first, middle and last of the 5 envs
>>> scales = np.tile(np.array([1.0, 0.75, 0.5]), (3, 1))
>>> prims.set_local_scales(scales, indices=np.array([0, 2, 4]))
set_max_efforts(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set maximum efforts for articulation in the view

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – maximum efforts for articulations in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Example:

>>> # set the max efforts for all the articulation joints to the indicated values.
>>> # Since there are 5 envs, the joint efforts are repeated 5 times
>>> max_efforts = np.tile(np.array([10000, 9000, 8000, 7000, 6000, 5000, 4000, 1000, 1000]), (num_envs, 1))
>>> prims.set_max_efforts(max_efforts)
>>>
>>> # set the fingers max efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 1000
>>> # for the first, middle and last of the 5 envs
>>> max_efforts = np.tile(np.array([1000, 1000]), (3, 1))
>>> prims.set_max_efforts(max_efforts, indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
set_max_joint_velocities(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set maximum velocities for articulation in the view

Parameters
  • values (Union[np.ndarray, torch.Tensor, wp.array]) – maximum velocities for articulations in the view. shape (M, K).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

set_sleep_thresholds(thresholds: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the threshold for articulations to enter a sleep state

Search for Articulations and Sleeping in PhysX docs for more details

Parameters
  • thresholds (Union[np.ndarray, torch.Tensor, wp.array]) – sleep thresholds to be applied. shape (M,).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the sleep threshold for all envs
>>> prims.set_sleep_thresholds(np.full((num_envs,), 0.01))
>>>
>>> # set only the sleep threshold for the first, middle and last of the 5 envs
>>> prims.set_sleep_thresholds(np.full((3,), 0.01), indices=np.array([0, 2, 4]))
set_solver_position_iteration_counts(counts: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the solver (position) iteration count for the articulations

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
  • counts (Union[np.ndarray, torch.Tensor, wp.array]) – number of iterations for the solver. Shape (M,).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the position iteration count for all envs
>>> prims.set_solver_position_iteration_counts(np.full((num_envs,), 64))
>>>
>>> # set only the position iteration count for the first, middle and last of the 5 envs
>>> prims.set_solver_position_iteration_counts(np.full((3,), 64), indices=np.array([0, 2, 4]))
set_solver_velocity_iteration_counts(counts: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Set the solver (velocity) iteration count for the articulations

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
  • counts (Union[np.ndarray, torch.Tensor, wp.array]) – number of iterations for the solver. Shape (M,).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the velocity iteration count for all envs
>>> prims.set_solver_velocity_iteration_counts(np.full((num_envs,), 64))
>>>
>>> # set only the velocity iteration count for the first, middle and last of the 5 envs
>>> prims.set_solver_velocity_iteration_counts(np.full((3,), 64), indices=np.array([0, 2, 4]))
set_stabilization_thresholds(thresholds: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

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
  • thresholds (Union[np.ndarray, torch.Tensor, wp.array]) – stabilization thresholds to be applied. Shape (M,).

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set the stabilization threshold for all envs
>>> prims.set_stabilization_thresholds(np.full((num_envs,), 0.005))
>>>
>>> # set only the stabilization threshold for the first, middle and last of the 5 envs
>>> prims.set_stabilization_thresholds(np.full((3,), 0.0051), indices=np.array([0, 2, 4]))
set_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set the linear and angular velocities of the prims in the view at once.

The method does this through the PhysX API only. It has to be called after initialization

Warning

This method will immediately set the articulation state

Parameters
  • velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – linear and angular velocities respectively to set the rigid prims to. shape is (M, 6).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Hint

This method belongs to the methods used to set the articulation kinematic state:

set_velocities (set_linear_velocities, set_angular_velocities), set_joint_positions, set_joint_velocities, set_joint_efforts

Example:

>>> # set each articulation linear velocity to (1., 1., 1.) and angular velocity to (.1, .1, .1)
>>> velocities = np.ones((num_envs, 6))
>>> velocities[:,3:] = 0.1
>>> prims.set_velocities(velocities)
>>>
>>> # set only the articulation velocities for the first, middle and last of the 5 envs
>>> velocities = np.ones((3, 6))
>>> velocities[:,3:] = 0.1
>>> prims.set_velocities(velocities, indices=np.array([0, 2, 4]))
set_visibilities(visibilities: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None

Set the visibilities of the prims in stage

Parameters
  • visibilities (Union[np.ndarray, torch.Tensor, wp.array]) – flag to set the visibilities of the usd prims in stage. Shape (M,). Where M <= size of the encapsulated prims in the view.

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Defaults to None (i.e: all prims in the view).

Example:

>>> # make all prims not visible in the stage
>>> prims.set_visibilities(visibilities=[False] * num_envs)
set_world_poses(positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, usd: bool = True) None

Set poses of prims in the view with respect to the world’s frame.

Warning

This method will change (teleport) the prim poses immediately to the indicated value

Parameters
  • positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – positions in the world frame of the prim. shape is (M, 3). Defaults to None, which means left unchanged.

  • orientations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – quaternion orientations in the world frame of the prims. quaternion is scalar-first (w, x, y, z). shape is (M, 4). Defaults to None, which means left unchanged.

  • indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • usd (bool, optional) – True to query from usd. Otherwise False to query from Fabric data. Defaults to True.

Hint

This method belongs to the methods used to set the prim state

Example:

>>> # reposition all articulations in row (x-axis)
>>> positions = np.zeros((num_envs, 3))
>>> positions[:,0] = np.arange(num_envs)
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (num_envs, 1))
>>> prims.set_world_poses(positions, orientations)
>>>
>>> # reposition only the articulations for the first, middle and last of the 5 envs in column (y-axis)
>>> positions = np.zeros((3, 3))
>>> positions[:,1] = np.arange(3)
>>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (3, 1))
>>> prims.set_world_poses(positions, orientations, indices=np.array([0, 2, 4]))
switch_control_mode(mode: str, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, joint_indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Switch control mode between "position", "velocity", or "effort" for all joints

This method will set the implicit Proportional-Derivative (PD) controller’s Kps (stiffnesses) and Kds (dampings), defined via the set_gains method, of the selected articulations and joints according to the following rule:

Control mode

Stiffnesses

Dampings

"position"

Kps

Kds

"velocity"

0

Kds

"effort"

0

0

Parameters
  • mode (str) – control mode to switch the articulations specified to. It can be "position", "velocity", or "effort"

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • joint_indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – joint indices to specify which joints to manipulate. Shape (K,). Where K <= num of dofs. Defaults to None (i.e: all dofs).

Example:

>>> # set 'velocity' as control mode for all joints
>>> prims.switch_control_mode("velocity")
>>>
>>> # set 'effort' as control mode only for the fingers: panda_finger_joint1 (7) and panda_finger_joint2 (8)
>>> # for the first, middle and last of the 5 envs
>>> prims.switch_control_mode("effort", indices=np.array([0, 2, 4]), joint_indices=np.array([7, 8]))
switch_dof_control_mode(mode: str, dof_index: int, indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None

Switch control mode between "position", "velocity", or "effort" for the specified DOF

This method will set the implicit Proportional-Derivative (PD) controller’s Kps (stiffnesses) and Kds (dampings), defined via the set_gains method, of the selected DOF according to the following rule:

Control mode

Stiffnesses

Dampings

"position"

Kps

Kds

"velocity"

0

Kds

"effort"

0

0

Parameters
  • mode (str) – control mode to switch the DOF specified to. It can be "position", "velocity" or "effort"

  • dof_index (int) – dof index to switch the control mode of.

  • indices (Optional[Union[np.ndarray, List, torch.Tensor, wp.array]], optional) – indices to specify which prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Example:

>>> # set 'velocity' as control mode for the panda_joint1 (0) joint for all envs
>>> prims.switch_dof_control_mode("velocity", dof_index=0)
>>>
>>> # set 'effort' as control mode for the panda_joint1 (0) for the first, middle and last of the 5 envs
>>> prims.switch_dof_control_mode("effort", dof_index=0, indices=np.array([0, 2, 4]))

ArticulationController

class ArticulationController

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Checkout the required tutorials at

https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

get_applied_action() omni.isaac.core.utils.types.ArticulationAction
Raises

Exception – [description]

Returns

Gets last applied action.

Return type

ArticulationAction

get_effort_modes() List[str]

[summary]

Raises
  • Exception – [description]

  • NotImplementedError – [description]

Returns

[description]

Return type

np.ndarray

get_gains() Tuple[numpy.ndarray, numpy.ndarray]

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

Tuple[np.ndarray, np.ndarray]

get_joint_limits() Tuple[numpy.ndarray, numpy.ndarray]

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

Tuple[np.ndarray, np.ndarray]

get_max_efforts() numpy.ndarray

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

np.ndarray

initialize(articulation_view) None

[summary]

Parameters

articulation_view ([type]) – [description]

set_effort_modes(mode: str, joint_indices: Optional[Union[numpy.ndarray, list]] = None) None

[summary]

Parameters
  • mode (str) – [description]

  • indices (Optional[Union[np.ndarray, list]], optional) – [description]. Defaults to None.

Raises
  • Exception – [description]

  • Exception – [description]

set_gains(kps: Optional[numpy.ndarray] = None, kds: Optional[numpy.ndarray] = None, save_to_usd: bool = False) None

[summary]

Parameters
  • kps (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • kds (Optional[np.ndarray], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_max_efforts(values: numpy.ndarray, joint_indices: Optional[Union[numpy.ndarray, list]] = None) None

[summary]

Parameters
  • value (float, optional) – [description]. Defaults to None.

  • indices (Optional[Union[np.ndarray, list]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

switch_control_mode(mode: str) None

[summary]

Parameters

mode (str) – [description]

Raises

Exception – [description]

switch_dof_control_mode(dof_index: int, mode: str) None

[summary]

Parameters
  • dof_index (int) – [description]

  • mode (str) – [description]

Raises

Exception – [description]

Loggers

DataLogger

class DataLogger

This class takes care of collecting data as well as reading already saved data in order to replay it for instance.

add_data(data: dict, current_time_step: float, current_time: float) None

Adds data to the log

Parameters
  • data (dict) – Dictionary representing the data to be logged at this time index.

  • current_time_step (float) – time step corresponding to the data collected.

  • current_time (float) – time in seconds corresponding to the data collected.

add_data_frame_logging_func(func: Callable[[List[omni.isaac.core.tasks.base_task.BaseTask], omni.isaac.core.scenes.scene.Scene], Dict]) None
Parameters

func (Callable[[list[BaseTask], Scene], None]) –

function to be called at every step when the logger is started. should follow:

def dummy_data_collection_fn(tasks, scene):

return {“data 1”: [data]}

get_data_frame(data_frame_index: int) omni.isaac.core.utils.types.DataFrame
Parameters

data_frame_index (int) – index of the data frame to retrieve.

Returns

Data Frame collected/ retrieved at the specified data frame index.

Return type

DataFrame

get_num_of_data_frames() int
Returns

the number of data frames collected/ retrieved in the data logger.

Return type

int

is_started() bool
Returns

True if data collection is started/ resumed. False otherwise.

Return type

bool

load(log_path: str) None

Loads data from a json file to read back a previous saved data or to resume recording data from another time step.

Parameters

log_path (str) – path of the json file to be used to load the data.

pause() None

Pauses data collection.

reset() None

Clears the data in the logger.

save(log_path: str) None

Saves the current data in the logger to a json file

Parameters

log_path (str) – path of the json file to be used to save the data.

start() None

Resumes/ starts data collection.

Materials

Visual Material

class VisualMaterial(name: str, prim_path: str, prim: pxr.Usd.Prim, shaders_list: List[pxr.UsdShade.Shader], material: pxr.UsdShade.Material)

[summary]

Parameters
  • name (str) – [description]

  • prim_path (str) – [description]

  • prim (Usd.Prim) – [description]

  • shaders_list (list[UsdShade.Shader]) – [description]

  • material (UsdShade.Material) – [description]

property material: pxr.UsdShade.Material

[summary]

Returns

[description]

Return type

UsdShade.Material

property name: str

[summary]

Returns

[description]

Return type

str

property prim: pxr.Usd.Prim

[summary]

Returns

[description]

Return type

Usd.Prim

property prim_path: str

[summary]

Returns

[description]

Return type

str

property shaders_list: List[pxr.UsdShade.Shader]

[summary]

Returns

[description]

Return type

[type]

Preview Surface

class PreviewSurface(prim_path: str, name: str = 'preview_surface', shader: Optional[pxr.UsdShade.Shader] = None, color: Optional[numpy.ndarray] = None, roughness: Optional[float] = None, metallic: Optional[float] = None)

[summary]

Parameters
  • prim_path (str) – [description]

  • name (str, optional) – [description]. Defaults to “preview_surface”.

  • shader (Optional[UsdShade.Shader], optional) – [description]. Defaults to None.

  • color (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • roughness (Optional[float], optional) – [description]. Defaults to None.

  • metallic (Optional[float], optional) – [description]. Defaults to None.

get_color() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_metallic() float

[summary]

Returns

[description]

Return type

float

get_roughness() float

[summary]

Returns

[description]

Return type

float

property material: pxr.UsdShade.Material

[summary]

Returns

[description]

Return type

UsdShade.Material

property name: str

[summary]

Returns

[description]

Return type

str

property prim: pxr.Usd.Prim

[summary]

Returns

[description]

Return type

Usd.Prim

property prim_path: str

[summary]

Returns

[description]

Return type

str

set_color(color: numpy.ndarray) None

[summary]

Parameters

color (np.ndarray) – [description]

set_metallic(metallic: float) None

[summary]

Parameters

metallic (float) – [description]

set_roughness(roughness: float) None

[summary]

Parameters

roughness (float) – [description]

property shaders_list: List[pxr.UsdShade.Shader]

[summary]

Returns

[description]

Return type

[type]

OmniPBR Material

class OmniPBR(prim_path: str, name: str = 'omni_pbr', shader: Optional[pxr.UsdShade.Shader] = None, texture_path: Optional[str] = None, texture_scale: Optional[numpy.ndarray] = None, texture_translate: Optional[numpy.ndarray] = None, color: Optional[numpy.ndarray] = None)

[summary]

Parameters
  • prim_path (str) – [description]

  • name (str, optional) – [description]. Defaults to “omni_pbr”.

  • shader (Optional[UsdShade.Shader], optional) – [description]. Defaults to None.

  • texture_path (Optional[str], optional) – [description]. Defaults to None.

  • texture_scale (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • texture_translate (Optional[np.ndarray, optional) – [description]. Defaults to None.

  • color (Optional[np.ndarray], optional) – [description]. Defaults to None.

get_color() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_metallic_constant() float

[summary]

Returns

[description]

Return type

float

get_project_uvw() bool

[summary]

Returns

[description]

Return type

bool

get_reflection_roughness() float

[summary]

Returns

[description]

Return type

float

get_texture() str

[summary]

Returns

[description]

Return type

str

get_texture_scale() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_texture_translate() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

property material: pxr.UsdShade.Material

[summary]

Returns

[description]

Return type

UsdShade.Material

property name: str

[summary]

Returns

[description]

Return type

str

property prim: pxr.Usd.Prim

[summary]

Returns

[description]

Return type

Usd.Prim

property prim_path: str

[summary]

Returns

[description]

Return type

str

set_color(color: numpy.ndarray) None

[summary]

Parameters

color (np.ndarray) – [description]

set_metallic_constant(amount: float) None

[summary]

Parameters

amount (float) – [description]

set_project_uvw(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_reflection_roughness(amount: float) None

[summary]

Parameters

amount (float) – [description]

set_texture(path: str) None

[summary]

Parameters

path (str) – [description]

set_texture_scale(x: float, y: float) None

[summary]

Parameters
  • x (float) – [description]

  • y (float) – [description]

set_texture_translate(x: float, y: float) None

[summary]

Parameters
  • x (float) – [description]

  • y (float) – [description]

property shaders_list: List[pxr.UsdShade.Shader]

[summary]

Returns

[description]

Return type

[type]

Omni Glass Material

class OmniGlass(prim_path: str, name: str = 'omni_glass', shader: Optional[pxr.UsdShade.Shader] = None, color: Optional[numpy.ndarray] = None, ior: Optional[float] = None, depth: Optional[float] = None, thin_walled: Optional[bool] = None)

[summary]

Parameters
  • prim_path (str) – [description]

  • name (str, optional) – [description]. Defaults to “omni_glass”.

  • shader (Optional[UsdShade.Shader], optional) – [description]. Defaults to None.

  • color (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • ior (Optional[float], optional) – [description]. Defaults to None.

  • depth (Optional[float], optional) – [description]. Defaults to None.

  • thin_walled (Optional[bool], optional) – [description]. Defaults to None.

Raises

Exception – [description]

get_color() Optional[numpy.ndarray]

[summary]

Returns

[description]

Return type

np.ndarray

get_depth() Optional[float]
get_ior() Optional[float]
get_thin_walled() Optional[float]
property material: pxr.UsdShade.Material

[summary]

Returns

[description]

Return type

UsdShade.Material

property name: str

[summary]

Returns

[description]

Return type

str

property prim: pxr.Usd.Prim

[summary]

Returns

[description]

Return type

Usd.Prim

property prim_path: str

[summary]

Returns

[description]

Return type

str

set_color(color: numpy.ndarray) None

[summary]

Parameters

color (np.ndarray) – [description]

set_depth(depth: float) None
set_ior(ior: float) None
set_thin_walled(thin_walled: float) None
property shaders_list: List[pxr.UsdShade.Shader]

[summary]

Returns

[description]

Return type

[type]

Physics Material

class PhysicsMaterial(prim_path: str, name: str = 'physics_material', static_friction: Optional[float] = None, dynamic_friction: Optional[float] = None, restitution: Optional[float] = None)

[summary]

Parameters
  • prim_path (str) – [description]

  • name (str, optional) – [description]. Defaults to “physics_material”.

  • static_friction (Optional[float], optional) – [description]. Defaults to None.

  • dynamic_friction (Optional[float], optional) – [description]. Defaults to None.

  • restitution (Optional[float], optional) – [description]. Defaults to None.

get_dynamic_friction() float

[summary]

Returns

[description]

Return type

float

get_restitution() float

[summary]

Returns

[description]

Return type

float

get_static_friction() float

[summary]

Returns

[description]

Return type

float

property material: pxr.UsdShade.Material

[summary]

Returns

[description]

Return type

UsdShade.Material

property name: str

[summary]

Returns

[description]

Return type

str

property prim: pxr.Usd.Prim

[summary]

Returns

[description]

Return type

Usd.Prim

property prim_path: str

[summary]

Returns

[description]

Return type

str

set_dynamic_friction(friction: float) None

[summary]

Parameters

friction (float) – [description]

set_restitution(restitution: float) None

[summary]

Parameters

restitution (float) – [description]

set_static_friction(friction: float) None

[summary]

Parameters

friction (float) – [description]

Particle Material

class ParticleMaterial(prim_path: str, name: Optional[str] = 'particle_material', friction: Optional[float] = None, particle_friction_scale: Optional[float] = None, damping: Optional[float] = None, viscosity: Optional[float] = None, vorticity_confinement: Optional[float] = None, surface_tension: Optional[float] = None, cohesion: Optional[float] = None, adhesion: Optional[float] = None, particle_adhesion_scale: Optional[float] = None, adhesion_offset_scale: Optional[float] = None, gravity_scale: Optional[float] = None, lift: Optional[float] = None, drag: Optional[float] = None)

A wrapper around position-based-dynamics (PBD) material for particles used to simulate fluids, cloth and inflatables.

Note

Currently, only a single material per particle system is supported which applies to all objects that are associated with the system.

get_adhesion() float
Returns

The adhesion for interaction between particles (solid or fluid), and rigids or deformables.

Return type

float

get_adhesion_offset_scale() float
Returns

The adhesion offset scale.

Return type

float

get_cohesion() float
Returns

The cohesion for interaction between fluid particles.

Return type

float

get_damping() float
Returns

The global velocity damping coefficient.

Return type

float

get_drag() float
Returns

The drag coefficient, basic aerodynamic drag model coefficient.

Return type

float

get_friction() float
Returns

The friction coefficient.

Return type

float

get_gravity_scale() float
Returns

The gravitational acceleration scaling factor.

Return type

float

get_lift() float
Returns

The lift coefficient, basic aerodynamic lift model coefficient.

Return type

float

get_particle_adhesion_scale() float
Returns

The particle adhesion scale.

Return type

float

get_particle_friction_scale() float
Returns

The particle friction scale.

Return type

float

get_surface_tension() float
Returns

The surface tension for fluid particles.

Return type

float

get_viscosity() float
Returns

The viscosity.

Return type

float

get_vorticity_confinement() float
Returns

The vorticity confinement for fluid particles.

Return type

float

initialize(physics_sim_view=None) None
is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

property material: pxr.UsdShade.Material

Returns: UsdShade.Material: The USD Material object.

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

post_reset() None

Resets the prim to its default state.

property prim: pxr.Usd.Prim

Returns: Usd.Prim: The USD prim present.

property prim_path: str

Returns: str: The stage path to the material.

set_adhesion(value: float) None

Sets the adhesion for interaction between particles (solid or fluid), and rigid or deformable objects.

Note

Adhesion also applies to solid-solid particle interactions, but is multiplied with the particle adhesion scale.

Parameters

value (float) – The adhesion. Range: [0, inf), Units: dimensionless

set_adhesion_offset_scale(value: float) None

Sets the adhesion offset scale.

It defines the offset at which adhesion ceases to take effect. For interactions between particles (fluid or solid), and rigids or deformables, the adhesion offset is defined relative to the rest offset. For solid particle-particle interactions, the adhesion offset is defined relative to the solid rest offset.

Parameters

value (float) – The adhesion offset scale. Range: [0, inf), Units: dimensionless

set_cohesion(value: float) None

Sets the cohesion for interaction between fluid particles.

Parameters

value (float) – The cohesion. Range: [0, inf), Units: dimensionless

set_damping(value: float) None

Sets the global velocity damping coefficient.

Parameters

value (float) – The damping coefficient. Range: [0, inf), Units: dimensionless

set_drag(value: float) None

Sets the drag coefficient, i.e. basic aerodynamic drag model coefficient.

It is useful for cloth and inflatable particle objects.

Parameters

value (float) – The drag coefficient. Range: [0, inf), Units: dimensionless

set_friction(value: float) None

Sets the friction coefficient.

The friction takes effect in all interactions between particles and rigids or deformables. For solid particle-particle interactions it is multiplied by the particle friction scale.

Parameters

value (float) – The friction coefficient. Range: [0, inf), Units: dimensionless

set_gravity_scale(value: float) None

Sets the gravitational acceleration scaling factor.

It can be used to approximate lighter-than-air inflatable. For example (-1.0 would invert gravity).

Parameters

value (float) – The gravity scale. Range: (-inf , inf), Units: dimensionless

set_lift(value: float) None

Sets the lift coefficient, i.e. basic aerodynamic lift model coefficient.

It is useful for cloth and inflatable particle objects.

Parameters

value (float) – The lift coefficient. Range: [0, inf), Units: dimensionless

set_particle_adhesion_scale(value: float) None

Sets the particle adhesion scale.

This coefficient scales the adhesion for solid particle-particle interaction.

Parameters

value (float) – The adhesion scale. Range: [0, inf), Units: dimensionless

set_particle_friction_scale(value: float) None

Sets the particle friction scale.

The coefficient that scales friction for solid particle-particle interaction.

Parameters

value (float) – The particle friction scale. Range: [0, inf), Units: dimensionless

set_surface_tension(value: float) None

Sets the surface tension for fluid particles.

Parameters

value (float) – The surface tension. Range: [0, inf), Units: 1 / (distance * distance * distance)

set_viscosity(value: float) None

Sets the viscosity for fluid particles.

Parameters

value (float) – The viscosity. Range: [0, inf), Units: dimensionless

set_vorticity_confinement(value: float) None

Sets the vorticity confinement for fluid particles.

This helps prevent energy loss due to numerical solver by adding vortex-like accelerations to the particles.

Parameters

value (float) – The vorticity confinement. Range: [0, inf), Units: dimensionless

Particle Material View

class ParticleMaterialView(prim_paths_expr: str, name: str = 'particle_material_view', frictions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_friction_scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, dampings: Optional[Union[numpy.ndarray, torch.Tensor]] = None, viscosities: Optional[Union[numpy.ndarray, torch.Tensor]] = None, vorticity_confinements: Optional[Union[numpy.ndarray, torch.Tensor]] = None, surface_tensions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, cohesions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, adhesions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_adhesion_scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, adhesion_offset_scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, gravity_scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, lifts: Optional[Union[numpy.ndarray, torch.Tensor]] = None, drags: Optional[Union[numpy.ndarray, torch.Tensor]] = None)

The view class to deal with particleMaterial prims. Provides high level functions to deal with particle material (1 or more particle materials) as well as its attributes/ properties. This object wraps all matching materials found at the regex provided at the prim_paths_expr. This object wraps all matching materials Prims found at the regex provided at the prim_paths_expr.

property count: int

Returns: int: number of rigid shapes for the prims in the view.

get_adhesion_offset_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the adhesion offset scale of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

adhesion offset scale tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_adhesions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the adhesion of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

adhesion tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_cohesions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the cohesion of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

cohesion tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_dampings(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the dampings of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

dampings tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_drags(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the drags of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

drag tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_frictions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the friction of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

friction tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_gravity_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the gravity scale of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

gravity scale tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_lifts(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the lifts of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

lift tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_particle_adhesion_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the adhesion scale of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

adhesion scale tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_particle_friction_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the particle friction scale of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

particle friction scale tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_surface_tensions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the surface tension of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

surface tension tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_viscosities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the viscosity of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

viscosity tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_vorticity_confinements(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the vorticity confinement of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

vorticity confinement tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None

Create a physics simulation view if not passed and creates a rigid body view in physX.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

is_physics_handle_valid() bool
Returns

True if the physics handle of the view is valid (i.e physics is initialized for the view). Otherwise False.

Return type

bool

is_valid(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) bool
Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

True if all prim paths specified in the view correspond to a valid prim in stage. False otherwise.

Return type

bool

property name: str

Returns: str: name given to the view when instantiating it.

post_reset() None

Resets the particles to their initial states.

set_adhesion_offset_scales(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the adhesion offset scale for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material adhesion offset scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_adhesions(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle adhesion for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle adhesion scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_cohesions(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle cohesion for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle cohesion scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_dampings(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the dampings for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material damping tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_drags(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the drags for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material drag tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_frictions(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the friction for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material friction tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_gravity_scales(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the gravity scale for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material gravity scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_lifts(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the lifts for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material lift tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_particle_adhesion_scales(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle adhesion for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle adhesion scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_particle_friction_scales(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle friction scale for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle friction scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_surface_tensions(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle surface tension for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle surface tension scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_viscosities(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the particle viscosity for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle viscosity scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_vorticity_confinements(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the vorticity confinement for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material particle vorticity confinement scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Deformable Material

class DeformableMaterial(prim_path: str, name: Optional[str] = 'deformable_material', dynamic_friction: Optional[float] = None, youngs_modulus: Optional[float] = None, poissons_ratio: Optional[float] = None, elasticity_damping: Optional[float] = None, damping_scale: Optional[float] = None)

A wrapper around deformable material used to simulate soft bodies.

get_damping_scale() float
Returns

The damping scale coefficient.

Return type

float

get_dynamic_friction() float
Returns

The dynamic friction coefficient.

Return type

float

get_elasticity_damping() float
Returns

The elasticity damping coefficient.

Return type

float

get_poissons_ratio() float
Returns

The poissons ratio.

Return type

float

get_youngs_modululs() float
Returns

The youngs modululs coefficient.

Return type

float

initialize(physics_sim_view=None) None
is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

property material: pxr.UsdShade.Material

Returns: UsdShade.Material: The USD Material object.

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

post_reset() None

Resets the prim to its default state.

property prim: pxr.Usd.Prim

Returns: Usd.Prim: The USD prim present.

property prim_path: str

Returns: str: The stage path to the material.

set_damping_scale(value: float) None

Sets the damping scale coefficient.

Parameters

value (float) – The damping scale coefficient Range: [0, inf)

set_dynamic_friction(value: float) None

Sets the dynamic_friction coefficient.

The dynamic_friction takes effect in all interactions between particles and rigids or deformables. For solid particle-particle interactions it is multiplied by the particle dynamic_friction scale.

Parameters

value (float) – The dynamic_friction coefficient. Range: [0, inf), Units: dimensionless

set_elasticity_damping(value: float) None

Sets the global velocity elasticity damping coefficient.

Parameters

value (float) – The elasticity damping coefficient. Range: [0, inf), Units: dimensionless

set_poissons_ratio(value: float) None

Sets the poissons ratio coefficient

Parameters

value (float) – The poissons ratio. Range: (0 , 0.5)

set_youngs_modululs(value: float) None

Sets the youngs_modululs for fluid particles.

Parameters

value (float) – The youngs_modululs. Range: [0, inf)

Deformable Material View

class DeformableMaterialView(prim_paths_expr: str, name: str = 'deformable_material_view', dynamic_frictions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, youngs_moduli: Optional[Union[numpy.ndarray, torch.Tensor]] = None, poissons_ratios: Optional[Union[numpy.ndarray, torch.Tensor]] = None, elasticity_dampings: Optional[Union[numpy.ndarray, torch.Tensor]] = None, damping_scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None)

The view class to deal with deformableMaterial prims. Provides high level functions to deal with deformable material (1 or more deformable materials) as well as its attributes/ properties. This object wraps all matching materials found at the regex provided at the prim_paths_expr. This object wraps all matching materials Prims found at the regex provided at the prim_paths_expr.

property count: int

Returns: int: number of rigid shapes for the prims in the view.

get_damping_scales(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the damping scale of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

damping scale tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_dynamic_frictions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the dynamic friction of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

dynamic friction tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_elasticity_dampings(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the elasticity dampings of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

elasticity dampings tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_poissons_ratios(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the poissons ratios of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

poissons ratio tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

get_youngs_moduli(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]

Gets the Youngs moduli of materials indicated by the indices.

Parameters
  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

  • clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.

Returns

Youngs moduli tensor with shape (M, )

Return type

Union[np.ndarray, torch.Tensor]

initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None

Create a physics simulation view if not passed and creates a rigid body view in physX.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

is_physics_handle_valid() bool
Returns

True if the physics handle of the view is valid (i.e physics is initialized for the view). Otherwise False.

Return type

bool

is_valid(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) bool
Parameters

indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which prims to query. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

Returns

True if all prim paths specified in the view correspond to a valid prim in stage. False otherwise.

Return type

bool

property name: str

Returns: str: name given to the view when instantiating it.

post_reset() None

Resets the deformables to their initial states.

set_damping_scales(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the damping scale for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material damping scale tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_dynamic_frictions(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the dynamic friction for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material dynamic friction tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_elasticity_dampings(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the elasticity_dampings for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material damping tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_poissons_ratios(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the poissons ratios for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material poissons ratio tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).

set_youngs_moduli(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None

Sets the youngs moduli for the material prims indicated by the indices.

Parameters
  • values (Optional[Union[np.ndarray, torch.Tensor]], optional) – material drag tensor with the shape (M, ).

  • indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which material prims to manipulate. Shape (M,). Where M <= size of the encapsulated prims in the view. Defaults to None (i.e: all prims in the view).


Objects

Modules to create/encapsulate visual, fixed, and dynamic shapes (Capsule, Cone, Cuboid, Cylinder, Sphere) as well as ground planes

Type

Classes

Collider API

Rigid Body API

Visual

omni.isaac.core.objects.VisualCapsule
omni.isaac.core.objects.VisualCone
omni.isaac.core.objects.VisualCuboid
omni.isaac.core.objects.VisualCylinder
omni.isaac.core.objects.VisualSphere

No

No

Fixed

omni.isaac.core.objects.FixedCapsule
omni.isaac.core.objects.FixedCone
omni.isaac.core.objects.FixedCuboid
omni.isaac.core.objects.FixedCylinder
omni.isaac.core.objects.FixedSphere

omni.isaac.core.objects.GroundPlane

Yes

No

Dynamic

omni.isaac.core.objects.DynamicCapsule
omni.isaac.core.objects.DynamicCone
omni.isaac.core.objects.DynamicCuboid
omni.isaac.core.objects.DynamicCylinder
omni.isaac.core.objects.DynamicSphere

Yes

Yes


Ground Plane

class GroundPlane(prim_path: str, name: str = 'ground_plane', size: Optional[float] = None, z_position: Optional[float] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)

High level wrapper to create/encapsulate a ground plane

Parameters
  • prim_path (str) – prim path of the Prim to encapsulate or create

  • name (str, optional) – shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene. Defaults to “ground_plane”.

  • size (Optional[float], optional) – length of each edge. Defaults to 5000.0.

  • z_position (float, optional) – ground plane position in the z-axis. Defaults to 0.

  • scale (Optional[np.ndarray], optional) – local scale to be applied to the prim’s dimensions. Defaults to None.

  • visible (bool, optional) – set to false for an invisible prim in the stage while rendering. Defaults to True.

  • color (Optional[np.ndarray], optional) – color of the visual plane. Defaults to None.

  • physics_material_path (Optional[PhysicsMaterial], optional) – path of the physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.

  • visual_material (Optional[VisualMaterial], optional) – visual material to be applied to the held prim. Defaults to None. If not specified, a default visual material will be added.

  • static_friction (float, optional) – static friction coefficient. Defaults to 0.5.

  • dynamic_friction (float, optional) – dynamic friction coefficient. Defaults to 0.5.

  • restitution (float, optional) – restitution coefficient. Defaults to 0.8.

Example:

>>> from omni.isaac.core.objects import GroundPlane
>>> import numpy as np
>>>
>>> # create a ground plane placed at 0 in the z-axis
>>> plane = GroundPlane(prim_path="/World/GroundPlane", z_position=0)
>>> plane
<omni.isaac.core.objects.ground_plane.GroundPlane object at 0x7f15d003fb50>
apply_physics_material(physics_material: omni.isaac.core.materials.physics_material.PhysicsMaterial, weaker_than_descendants: bool = False)

Used to apply physics material to the held prim and optionally its descendants.

Parameters
  • physics_material (PhysicsMaterial) – physics material to be applied to the held prim. This where you want to define friction, restitution..etc. Note: if a physics material is not defined, the defaults will be used from PhysX.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

Example:

>>> from omni.isaac.core.materials import PhysicsMaterial
>>>
>>> # create a rigid body physical material
>>> material = PhysicsMaterial(
...     prim_path="/World/physics_material/aluminum",  # path to the material prim to create
...     dynamic_friction=0.4,
...     static_friction=1.1,
...     restitution=0.1
... )
>>> plane.apply_physics_material(material)
property collision_geometry_prim: omni.isaac.core.prims.geometry_prim.GeometryPrim
Returns

wrapped object as a GeometryPrim

Return type

GeometryPrim

Example:

>>> plane.collision_geometry_prim
<omni.isaac.core.prims.geometry_prim.GeometryPrim object at 0x7f15ff3461a0>
get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial

Returns the current applied physics material in case it was applied using apply_physics_material or not.

Returns

the current applied physics material.

Return type

PhysicsMaterial

Example:

>>> plane.get_applied_physics_material()
<omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f517ff62920>
get_default_state() omni.isaac.core.utils.types.XFormPrimState

Get the default prim states (spatial position and orientation).

Returns

an object that contains the default state of the prim (position and orientation)

Return type

XFormPrimState

Example:

>>> state = plane.get_default_state()
>>> state
<omni.isaac.core.utils.types.XFormPrimState object at 0x7f6efff41cf0>
>>>
>>> state.position
[0. 0. 0.]
>>> state.orientation
[1. 0. 0. 0.]
get_world_pose() Tuple[numpy.ndarray, numpy.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

Return type

Tuple[np.ndarray, np.ndarray]

Example:

>>> # if the prim is in position (0.0, 0.0, 0.0) with respect to the world frame
>>> position, orientation = prim.get_world_pose()
>>> position
[0. 0. 0.]
>>> orientation
[1. 0. 0. 0.]
initialize(physics_sim_view=None) None

Create a physics simulation view if not passed and using PhysX tensor API

Note

If the prim has been added to the world scene (e.g., world.scene.add(prim)), it will be automatically initialized when the world is reset (e.g., world.reset()).

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

Example:

>>> plane.initialize()
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.

Return type

bool

Example:

>>> # given an existing and valid prim
>>> plane.is_valid()
True
property name: Optional[str]
Returns

name given to the prim when instantiating it. Otherwise None.

Return type

str

Example:

>>> plane.name
ground_plane
post_reset() None

Reset the prim to its default state (position and orientation).

Example:

>>> plane.post_reset()
property prim: pxr.Usd.Prim
Returns

USD Prim object that this object holds.

Return type

Usd.Prim

Example:

>>> plane.prim
Usd.Prim(</World/GroundPlane>)
property prim_path: str
Returns

prim path in the stage.

Return type

str

Example:

>>> plane.prim_path
/World/GroundPlane
set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

Example:

>>> # configure default state
>>> plane.set_default_state(position=np.array([0.0, 0.0, -1.0]), orientation=np.array([1, 0, 0, 0]))
>>>
>>> # set default states during post-reset
>>> plane.post_reset()
set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Ses 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 (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

Hint

This method belongs to the methods used to set the prim state

Example:

>>> plane.set_world_pose(position=np.array([0.0, 0.0, 0.5]), orientation=np.array([1., 0., 0., 0.]))
property xform_prim: omni.isaac.core.prims.xform_prim.XFormPrim
Returns

wrapped object as a XFormPrim

Return type

XFormPrim

Example:

>>> plane.xform_prim
<omni.isaac.core.prims.xform_prim.XFormPrim object at 0x7f1578d32560>

Visual Capsule

class VisualCapsule(prim_path: str, name: str = 'visual_capsule', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]