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
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
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
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 typeArticulationController
(a Proportional-Derivative controller that can apply position targets, velocity targets and efforts) will be used- Returns
articulation controller
- Return type
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
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
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
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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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()
orworld.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
argumentNote
Each prim will have
xformOp:orient
,xformOp:translate
andxformOp: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
andset_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
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
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
orforce
- 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
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
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_link_index(link_name: str) int
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
- property is_non_root_articulation_link: bool
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 theset_joints_default_state
method) and the joint stiffnesses and dampings (defined via theset_gains
method) are imposedExample:
>>> 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()
orworld.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
orforce
.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 theapply_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 theapply_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()
orworld.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 jointsThis 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 DOFThis 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
- 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
- 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
- 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
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
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
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
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
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]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[float] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)
High level wrapper to create/encapsulate a visual capsule
Note
Visual capsules (Capsule shape) have no collisions (Collider API) or rigid body dynamics (Rigid Body API)
- 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 “visual_capsule”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – capsule radius. Defaults to None.
height (Optional[float], optional) – capsule height. Defaults to None.
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.
Example:
>>> from omni.isaac.core.objects import VisualCapsule >>> import numpy as np >>> >>> # create a red visual capsule at the given path ... prim = VisualCapsule( ... prim_path="/World/Xform/Capsule", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> prim <omni.isaac.core.objects.capsule.VisualCapsule object at 0x7f4ff958b0d0>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the capsule height
- Returns
capsule height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the capsule radius
- Returns
capsule radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the capsule height
- Parameters
height (float) – capsule height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the capsule radius
- Parameters
radius (float) – capsule radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Visual Cone
- class VisualCone(prim_path: str, name: str = 'visual_cone', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[float] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)
High level wrapper to create/encapsulate a visual cone
Note
Visual cones (Cone shape) have no collisions (Collider API) or rigid body dynamics (Rigid Body API)
- 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 “visual_cone”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cone height. Defaults to None.
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.
Example:
>>> from omni.isaac.core.objects import VisualCone >>> import numpy as np >>> >>> # create a red visual cone at the given path >>> prim = VisualCone( ... prim_path="/World/Xform/Cone", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> prim <omni.isaac.core.objects.cone.VisualCone object at 0x7f513413aa70>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cone height
- Returns
cone height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the cone height
- Parameters
height (float) – cone height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Visual Cuboid
- class VisualCuboid(prim_path: str, name: str = 'visual_cube', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, size: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)
High level wrapper to create/encapsulate a visual cuboid
Note
Visual cuboids (Cube shape) have no collisions (Collider API) or rigid body dynamics (Rigid Body API)
- 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 “visual_cube”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
size (Optional[float], optional) – length of each cube edge. Defaults to None.
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.
Example:
>>> from omni.isaac.core.objects import VisualCuboid >>> import numpy as np >>> >>> # create a red visual cube at the given path >>> prim = VisualCuboid(prim_path="/World/Xform/Cube", color=np.array([1.0, 0.0, 0.0])) >>> prim <omni.isaac.core.objects.cuboid.VisualCuboid object at 0x7f12e756fa00>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_size() numpy.ndarray
Get the length of each cube edge
- Returns
edge length
- Return type
float
Example:
>>> prim.get_size() 1.0
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_size(size: float) None
Set the length of each cube edge
- Parameters
size (float) – edge length
Example:
>>> prim.set_size(2.0)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Visual Cylinder
- class VisualCylinder(prim_path: str, name: str = 'visual_cylinder', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[float] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)
High level wrapper to create/encapsulate a visual cylinder
Note
Visual cylinders (Cylinder shape) have no collisions (Collider API) or rigid body dynamics (Rigid Body API)
- 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 “visual_cylinder”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cylinder height. Defaults to None.
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.
Example:
>>> from omni.isaac.core.objects import VisualCylinder >>> import numpy as np >>> >>> # create a red visual cylinder at the given path >>> prim = VisualCylinder( ... prim_path="/World/Xform/Cylinder", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> prim <omni.isaac.core.objects.cylinder.VisualCylinder object at 0x7f4e433f22c0>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cylinder height
- Returns
cylinder height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the cylinder height
- Parameters
height (float) – cylinder height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Visual Sphere
- class VisualSphere(prim_path: str, name: str = 'visual_sphere', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = True, color: Optional[numpy.ndarray] = None, radius: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None)
High level wrapper to create/encapsulate a visual sphere
Note
Visual spheres (Sphere shape) have no collisions (Collider API) or rigid body dynamics (Rigid Body API)
- 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 “visual_sphere”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – sphere radius. Defaults to None.
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.
Example:
>>> from omni.isaac.core.objects import VisualSphere >>> import numpy as np >>> >>> # create a red visual sphere at the given path >>> prim = VisualSphere(prim_path="/World/Xform/Sphere", color=np.array([1.0, 0.0, 0.0])) >>> prim <omni.isaac.core.objects.sphere.VisualSphere object at 0x7f4e3eb3ea70>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the sphere radius
- Returns
sphere radius
- Return type
float
Example:
>>> prim.get_radius() 1.0
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the sphere radius
- Parameters
radius (float) – sphere radius
Example:
>>> prim.set_radius(2.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Fixed Capsule
- class FixedCapsule(prim_path: str, name: str = 'fixed_capsule', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None)
High level wrapper to create/encapsulate a fixed capsule
Note
Fixed capsules (Capsule shape) have collisions (Collider API) but no rigid body dynamics (Rigid Body API)
- 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 “fixed_capsule”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – capsule radius. Defaults to None.
height (Optional[float], optional) – capsule height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
Example:
>>> from omni.isaac.core.objects import FixedCapsule >>> import numpy as np >>> >>> # create a red fixed capsule at the given path >>> prim = FixedCapsule( ... prim_path="/World/Xform/Capsule", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> print(prim) <omni.isaac.core.objects.capsule.FixedCapsule object at 0x7f520c0d4790>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the capsule height
- Returns
capsule height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the capsule radius
- Returns
capsule radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the capsule height
- Parameters
height (float) – capsule height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the capsule radius
- Parameters
radius (float) – capsule radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Fixed Cone
- class FixedCone(prim_path: str, name: str = 'fixed_cone', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None)
High level wrapper to create/encapsulate a fixed cone
Note
Fixed cones (Cone shape) have collisions (Collider API) but no rigid body dynamics (Rigid Body API)
- 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 “fixed_cone”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cone height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
Example:
>>> from omni.isaac.core.objects import FixedCone >>> import numpy as np >>> >>> # create a red fixed cone at the given path >>> prim = FixedCone( ... prim_path="/World/Xform/Cone", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> prim <omni.isaac.core.objects.cone.FixedCone object at 0x7f51489f09a0>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cone height
- Returns
cone height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the cone height
- Parameters
height (float) – cone height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Fixed Cuboid
- class FixedCuboid(prim_path: str, name: str = 'fixed_cube', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, size: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None)
High level wrapper to create/encapsulate a fixed cuboid
Note
Fixed cuboids (Cube shape) have collisions (Collider API) but no rigid body dynamics (Rigid Body API)
- 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 “fixed_cube”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
size (Optional[float], optional) – length of each cube edge. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
Example:
>>> from omni.isaac.core.objects import FixedCuboid >>> import numpy as np >>> >>> # create a red fixed cube at the given path >>> prim = FixedCuboid(prim_path="/World/Xform/Cube", color=np.array([1.0, 0.0, 0.0])) >>> prim <omni.isaac.core.objects.cuboid.FixedCuboid object at 0x7f7b4d91da80>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_size() numpy.ndarray
Get the length of each cube edge
- Returns
edge length
- Return type
float
Example:
>>> prim.get_size() 1.0
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_size(size: float) None
Set the length of each cube edge
- Parameters
size (float) – edge length
Example:
>>> prim.set_size(2.0)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Fixed Cylinder
- class FixedCylinder(prim_path: str, name: str = 'fixed_cylinder', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None)
High level wrapper to create/encapsulate a fixed cylinder
Note
Fixed cylinders (Cylinder shape) have collisions (Collider API) but no rigid body dynamics (Rigid Body API)
- 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 “fixed_cylinder”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cylinder height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
Example:
>>> from omni.isaac.core.objects import FixedCylinder >>> import numpy as np >>> >>> # create a red fixed cylinder at the given path >>> prim = FixedCylinder( ... prim_path="/World/Xform/Cylinder", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]) ... ) >>> print(prim) <omni.isaac.core.objects.cylinder.FixedCylinder object at 0x7f4f24144f40>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cylinder height
- Returns
cylinder height
- Return type
float
Example:
>>> prim.get_height() 1.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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_height(height: float) None
Set the cylinder height
- Parameters
height (float) – cylinder height
Example:
>>> prim.set_height(2.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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Fixed Sphere
- class FixedSphere(prim_path: str, name: str = 'fixed_sphere', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None)
High level wrapper to create/encapsulate a fixed sphere
Note
Fixed spheres (Sphere shape) have collisions (Collider API) but no rigid body dynamics (Rigid Body API)
- 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 “fixed_sphere”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – sphere radius. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
Example:
>>> from omni.isaac.core.objects import FixedSphere >>> import numpy as np >>> >>> # create a red fixed sphere at the given path >>> prim = FixedSphere(prim_path="/World/Xform/Sphere", color=np.array([1.0, 0.0, 0.0])) >>> prim <omni.isaac.core.objects.sphere.FixedSphere object at 0x7f4e433f2140>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the sphere radius
- Returns
sphere radius
- Return type
float
Example:
>>> prim.get_radius() 1.0
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the sphere radius
- Parameters
radius (float) – sphere radius
Example:
>>> prim.set_radius(2.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Dynamic Capsule
- class DynamicCapsule(prim_path: str, name: str = 'dynamic_capsule', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[numpy.ndarray] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[Sequence[float]] = None, angular_velocity: Optional[Sequence[float]] = None)
High level wrapper to create/encapsulate a dynamic capsule
Note
Dynamic capsules (Capsule shape) have collisions (Collider API) and rigid body dynamics (Rigid Body API)
- 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 “dynamic_capsule”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – capsule radius. Defaults to None.
height (Optional[float], optional) – capsule height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> from omni.isaac.core.objects import DynamicCapsule >>> import numpy as np >>> >>> # create a red fixed capsule of mass 1kg at the given path >>> prim = DynamicCapsule( ... prim_path="/World/Xform/Capsule", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]), ... mass=1.0 ... ) >>> prim <omni.isaac.core.objects.capsule.DynamicCapsule object at 0x7f4ff915f8e0>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the capsule height
- Returns
capsule height
- Return type
float
Example:
>>> prim.get_height() 1.0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the capsule radius
- Returns
capsule radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_height(height: float) None
Set the capsule height
- Parameters
height (float) – capsule height
Example:
>>> prim.set_height(2.0)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the capsule radius
- Parameters
radius (float) – capsule radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Dynamic Cone
- class DynamicCone(prim_path: str, name: str = 'dynamic_cone', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[numpy.ndarray] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[Sequence[float]] = None, angular_velocity: Optional[Sequence[float]] = None)
High level wrapper to create/encapsulate a dynamic cone
Note
Dynamic cones (Cone shape) have collisions (Collider API) and rigid body dynamics (Rigid Body API)
- 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 “dynamic_cone”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cone height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> from omni.isaac.core.objects import DynamicCone >>> import numpy as np >>> >>> # create a red dynamic cone of mass 1kg at the given path >>> prim = DynamicCone( ... prim_path="/World/Xform/Cone", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]), ... mass=1.0 ... ) >>> prim <omni.isaac.core.objects.cone.DynamicCone object at 0x7f4f9f5d11b0>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cone height
- Returns
cone height
- Return type
float
Example:
>>> prim.get_height() 1.0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_height(height: float) None
Set the cone height
- Parameters
height (float) – cone height
Example:
>>> prim.set_height(2.0)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Dynamic Cuboid
- class DynamicCuboid(prim_path: str, name: str = 'dynamic_cube', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, size: Optional[float] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[Sequence[float]] = None, angular_velocity: Optional[Sequence[float]] = None)
High level wrapper to create/encapsulate a dynamic cuboid
Note
Dynamic cuboids (Cube shape) have collisions (Collider API) and rigid body dynamics (Rigid Body API)
- 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 “fixed_cube”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
size (Optional[float], optional) – length of each cube edge. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> from omni.isaac.core.objects import DynamicCuboid >>> import numpy as np >>> >>> # create a red dynamic cube of mass 1kg at the given path >>> prim = DynamicCuboid(prim_path="/World/Xform/Cube", color=np.array([1.0, 0.0, 0.0]), mass=1.0) >>> prim <omni.isaac.core.objects.cuboid.DynamicCuboid object at 0x7ff14c04d990>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_size() numpy.ndarray
Get the length of each cube edge
- Returns
edge length
- Return type
float
Example:
>>> prim.get_size() 1.0
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_size(size: float) None
Set the length of each cube edge
- Parameters
size (float) – edge length
Example:
>>> prim.set_size(2.0)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Dynamic Cylinder
- class DynamicCylinder(prim_path: str, name: str = 'dynamic_cylinder', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, height: Optional[numpy.ndarray] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[Sequence[float]] = None, angular_velocity: Optional[Sequence[float]] = None)
High level wrapper to create/encapsulate a dynamic cylinder
Note
Dynamic cylinders (Cylinder shape) have collisions (Collider API) and rigid body dynamics (Rigid Body API)
- 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 “dynamic_cylinder”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – base radius. Defaults to None.
height (Optional[float], optional) – cylinder height. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> from omni.isaac.core.objects import DynamicCylinder >>> import numpy as np >>> >>> # create a red fixed cylinder of mass 1kg at the given path >>> prim = DynamicCylinder( ... prim_path="/World/Xform/Cylinder", ... radius=0.5, ... height=1.0, ... color=np.array([1.0, 0.0, 0.0]), ... mass=1.0 ... ) >>> prim <omni.isaac.core.objects.cylinder.DynamicCylinder object at 0x7f4e8f5c4a60>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_height() float
Get the cylinder height
- Returns
cylinder height
- Return type
float
Example:
>>> prim.get_height() 1.0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the base radius
- Returns
base radius
- Return type
float
Example:
>>> prim.get_radius() 0.5
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_height(height: float) None
Set the cylinder height
- Parameters
height (float) – cylinder height
Example:
>>> prim.set_height(2.0)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the base radius
- Parameters
radius (float) – base radius
Example:
>>> prim.set_radius(1.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Dynamic Sphere
- class DynamicSphere(prim_path: str, name: str = 'dynamic_sphere', position: Optional[numpy.ndarray] = None, translation: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, scale: Optional[numpy.ndarray] = None, visible: Optional[bool] = None, color: Optional[numpy.ndarray] = None, radius: Optional[numpy.ndarray] = None, visual_material: Optional[omni.isaac.core.materials.visual_material.VisualMaterial] = None, physics_material: Optional[omni.isaac.core.materials.physics_material.PhysicsMaterial] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[Sequence[float]] = None, angular_velocity: Optional[Sequence[float]] = None)
High level wrapper to create/encapsulate a dynamic sphere
Note
Dynamic spheres (Sphere shape) have collisions (Collider API) and rigid body dynamics (Rigid Body API)
- 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 “dynamic_sphere”.
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.
color (Optional[np.ndarray], optional) – color of the visual shape. Defaults to None, which means 50% gray
radius (Optional[float], optional) – sphere radius. Defaults to None.
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.
physics_material (Optional[PhysicsMaterial], optional) – physics material to be applied to the held prim. Defaults to None. If not specified, a default physics material will be added.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> from omni.isaac.core.objects import DynamicSphere >>> import numpy as np >>> >>> # create a red dynamic sphere of mass 1kg at the given path >>> prim = DynamicSphere(prim_path="/World/Xform/Sphere", color=np.array([1.0, 0.0, 0.0]), mass=1.0) >>> prim <omni.isaac.core.objects.sphere.DynamicSphere object at 0x7f4deaf8f010>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_radius() float
Get the sphere radius
- Returns
sphere radius
- Return type
float
Example:
>>> prim.get_radius() 1.0
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_radius(radius: float) None
Set the sphere radius
- Parameters
radius (float) – sphere radius
Example:
>>> prim.set_radius(2.0)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Physics Context
- class PhysicsContext(physics_dt: Optional[float] = None, prim_path: str = '/physicsScene', sim_params: Optional[dict] = None, set_defaults: bool = True, backend: str = 'numpy', device: Optional[str] = None)
- Provides high level functions to deal with a physics scene and its settings. This will create a
a PhysicsScene prim at the specified prim path in case there is no PhysicsScene present in the current stage. If there is a PhysicsScene present, it will discard the prim_path specified and sets the default settings on the current PhysicsScene found.
- Parameters
physics_dt (float, optional) – specifies the physics_dt of the simulation. Defaults to 1.0 / 60.0.
prim_path (Optional[str], optional) – specifies the prim path to create a PhysicsScene at, only in the case where no PhysicsScene already defined. Defaults to “/physicsScene”.
set_defaults (bool, optional) – set to True to use the defaults physics parameters [physics_dt = 1.0/ 60.0, gravity = -9.81 m / s ccd_enabled, stabilization_enabled, gpu dynamics turned off, broadcast type is MBP, solver type is TGS]. Defaults to True.
backend (str, optional) – specifies the backend to be used (numpy or torch). Defaults to numpy.
device (Optional[str], optional) – specifies the device to be used if running on the gpu with torch backend.
- Raises
Exception – If prim_path is not absolute.
Exception – if prim_path already exists and its type is not a PhysicsScene.
- property device: str
- enable_ccd(flag: bool) None
- Enables a second broad phase after integration that makes it possible to prevent objects from tunneling
through each other.
- Parameters
flag (bool) – enables or disables ccd on the PhysicsScene
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- enable_fabric(enable)
- enable_gpu_dynamics(flag: bool) None
Enables gpu dynamics pipeline, required for deformables for instance.
- Parameters
flag (bool) – enables or disables gpu dynamics on the PhysicsScene
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- enable_stablization(flag: bool) None
Enables additional stabilization pass in the solver.
- Parameters
flag (bool) – enables or disables stabilization on the PhysicsScene
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- get_bounce_threshold() float
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
float
- get_broadphase_type() str
Gets current broadcast phase algorithm type.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
Broadcast phase algorithm used.
- Return type
str
- get_current_physics_scene_prim() Optional[pxr.Usd.Prim]
Used to return the PhysicsScene prim in stage by traversing the stage.
- Returns
returns a PhysicsScene prim if found in current stage. Otherwise, None.
- Return type
Optional[Usd.Prim]
- get_enable_scene_query_support() bool
Retrieves the Enable Scene Query Support attribute in Physx Scene
- Raises
Exception – [description]
- Returns
enable scene query support attribute
- Return type
bool
- get_friction_correlation_distance() float
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
float
- get_friction_offset_threshold() float
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
float
- get_gpu_collision_stack_size() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_found_lost_aggregate_pairs_capacity() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_found_lost_pairs_capacity() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_heap_capacity() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_max_num_partitions() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_max_particle_contacts() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_max_rigid_contact_count() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_max_rigid_patch_count() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_max_soft_body_contacts() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_temp_buffer_capacity() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gpu_total_aggregate_pairs_capacity() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_gravity() Tuple[List, float]
Gets current gravity.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
returns a tuple, first element corresponds to the gravity direction vector and second element is the magnitude.
- Return type
Tuple[list, float]
- get_invert_collision_group_filter() int
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
int
- get_physics_dt() float
Returns the current physics dt.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
physics dt.
- Return type
float
- get_physx_update_transformations_settings() Tuple[bool, bool, bool, bool]
Gets how physx syncs with the usd when transformations are updated.
- Returns
[update_to_usd, update_velocities_to_usd, output_velocities_local_space]
- Return type
Tuple[bool, bool, bool, bool]
- get_solver_type() str
Gets current solver type.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
solver used for simulation.
- Return type
str
- is_ccd_enabled() bool
Checks if ccd is enabled.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
True if ccd is enabled, otherwise False.
- Return type
bool
- is_gpu_dynamics_enabled() bool
Checks if Gpu Dynamics is enabled.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
True if Gpu Dynamics is enabled, otherwise False.
- Return type
bool
- is_stablization_enabled() bool
Checks if stabilization is enabled.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- Returns
True if stabilization is enabled, otherwise False.
- Return type
bool
- property prim_path
- set_bounce_threshold(value: float) None
[summary]
- Parameters
value (float) – [description]
- Raises
Exception – [description]
- set_broadphase_type(broadcast_type: str) None
Broadcast phase algorithm used in simulation.
- Parameters
broadcast_type (str) – type of broadcasting to be used, can be “MBP”
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- set_enable_scene_query_support(enable_scene_query_support: bool) None
Sets the Enable Scene Query Support attribute in Physx Scene
- Parameters
enable_scene_query_support (bool) – Whether to enable scene query support
- Raises
Exception – [description]
- set_friction_correlation_distance(value: float) None
[summary]
- Parameters
value (float) – [description]
- Raises
Exception – [description]
- set_friction_offset_threshold(value: float) None
[summary]
- Parameters
value (float) – [description]
- Raises
Exception – [description]
- set_gpu_collision_stack_size(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_found_lost_aggregate_pairs_capacity(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_found_lost_pairs_capacity(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_heap_capacity(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_max_num_partitions(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_max_particle_contacts(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_max_rigid_contact_count(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_max_rigid_patch_count(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_max_soft_body_contacts(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_temp_buffer_capacity(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gpu_total_aggregate_pairs_capacity(value: int) None
[summary]
- Parameters
value (int) – [description]
- Raises
Exception – [description]
- set_gravity(value: float) None
sets the gravity direction and magnitude.
- Parameters
value (float) – gravity value to be used in simulation.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- set_invert_collision_group_filter(invert_collision_group_filter: bool) None
[summary]
- Parameters
invert_collision_group_filter (bool) – [description]
- Raises
Exception – [description]
- set_physics_dt(dt: float = 0.016666666666666666, substeps: int = 1) None
Sets the physics dt on the PhysicsScene
- Parameters
dt (float, optional) – physics dt. Defaults to 1.0/60.0.
substeps (int, optional) – number of physics steps to run for before rendering a frame. Defaults to 1.
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
ValueError – Physics dt must be a >= 0.
ValueError – Physics dt must be a <= 1.0.
- set_physx_update_transformations_settings(update_to_usd: Optional[bool] = None, update_velocities_to_usd: Optional[bool] = None, output_velocities_local_space: Optional[bool] = None) None
Sets how physx syncs with the usd when transformations are updated.
- Parameters
update_to_usd (bool, optional) – Updates to USD the transformations. Defaults to True.
update_velocities_to_usd (bool, optional) – Updates Velocities to USD. Defaults to True.
output_velocities_local_space (bool, optional) – Output the velocities in the local frame and not the world frame. Defaults to False.
- set_solver_type(solver_type: str) None
solver used for simulation.
- Parameters
solver_type (str) – can be “TGS” or “PGS”. for references look at..
- Raises
Exception – If the prim path registered in context doesn’t correspond to a valid prim path currently.
- property use_fabric
- property use_gpu_pipeline
- property use_gpu_sim
- warm_start()
Prims
Base Sensor
- class BaseSensor(prim_path: str, name: str = 'base_sensor', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None)
Provides a common properties and methods to deal with prims as a sensor
Note
This class, which inherits from
XFormPrim
, does not currently add any new property/method to it. Its definition is oriented to future implementations.- 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 “base_sensor”.
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.
- Raises
Exception – if translation and position defined at the same time
- 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)
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- 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
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_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_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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_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_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_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.]))
XForm Prim
- class XFormPrim(prim_path: str, name: str = 'xform_prim', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None)
Provides high level functions to deal with an Xform prim (only one Xform prim) and its attributes/properties
If there is an Xform prim present at the path, it will use it. Otherwise, a new XForm prim at the specified prim path will be created
Note
The prim will have
xformOp:orient
,xformOp:translate
andxformOp:scale
only post-init, unless it is a non-root articulation link.- 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 “xform_prim”.
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.
- Raises
Exception – if translation and position defined at the same time
Example:
>>> from omni.isaac.core.prims import XFormPrim >>> >>> # given the stage: /World. Get the Xform prim at /World >>> prim = XFormPrim("/World") >>> prim <omni.isaac.core.prims.xform_prim.XFormPrim object at 0x7f52381547c0> >>> >>> # create a new Xform prim at path: /World/Objects >>> prim = XFormPrim("/World/Objects", name="objects") >>> prim <omni.isaac.core.prims.xform_prim.XFormPrim object at 0x7f525c11d420>
- 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)
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- 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
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_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_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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_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_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_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.]))
XForm Prim View
- class XFormPrimView(prim_paths_expr: Union[str, List[str]], name: str = 'xform_prim_view', positions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, translations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, visibilities: Optional[Union[numpy.ndarray, torch.Tensor]] = None, reset_xform_properties: bool = True, usd: bool = True)
Provides high level functions to deal with a Xform prim view (one or many) and its descendants as well as its attributes/properties.
This class wraps all matching Xforms found at the regex provided at the
prim_paths_expr
argumentNote
Each prim will have
xformOp:orient
,xformOp:translate
andxformOp:scale
only post-init, unless it is a non-root articulation link.- 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 Xform). Additionally a list of regex can be provided. example [“/World/Env[1-5]/Franka”, “/World/Env[10-19]/Franka”].
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 “xform_prim_view”.
positions (Optional[Union[np.ndarray, torch.Tensor]], optional) – default positions in the world frame of the prim. shape is (N, 3). Defaults to None, which means left unchanged.
translations (Optional[Union[np.ndarray, torch.Tensor]], 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]], optional) – default quaternion orientations 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 (N, 4). Defaults to None, which means left unchanged.
scales (Optional[Union[np.ndarray, torch.Tensor]], optional) – local scales to be applied to the prim’s dimensions. shape is (N, 3). Defaults to None, which means left unchanged.
visibilities (Optional[Union[np.ndarray, torch.Tensor]], 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.
usd (bool, optional) – True to strictly read/ write from usd. Otherwise False to allow read/ write from Fabric during initialization. Defaults to True.
- Raises
Exception – if translations and positions defined at the same time.
Exception – No prim was matched using the prim_paths_expr provided.
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.cloner import GridCloner >>> from omni.isaac.core.prims import XFormPrimView >>> from pxr import UsdGeom >>> >>> 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) >>> env_pos = cloner.clone( ... source_prim_path=env_zero_path, ... prim_paths=cloner.generate_paths("/World/envs/env", num_envs), ... copy_from_source=True ... ) >>> >>> # wrap all Xforms >>> prims = XFormPrimView(prim_paths_expr="/World/envs/env.*", name="xform_view") >>> prims <omni.isaac.core.prims.xform_prim_view.XFormPrimView object at 0x7f8ffd22ebc0>
- 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 count: int
- Returns
Number of prims encapsulated in this view.
- Return type
int
Example:
>>> prims.count 5
- 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_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
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_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 translations 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 prims 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 [[ 1.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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 [[ 1.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> 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_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, 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).
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 prims 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.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> 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
For this particular class, calling this method will do nothing
- Parameters
physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.
Example:
>>> prims.initialize()
- property is_non_root_articulation_link: bool
Returns: bool: True if the prim corresponds to a non root link in an articulation. Otherwise False.
- 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 name: str
Returns: str: name given to the prims view when instantiating it.
- post_reset() None
Reset the prims to its default state (positions and orientations)
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>)]
- 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()
orworld.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_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 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_local_poses(positions, orientations) >>> >>> # reposition only the prims 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_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 prim poses 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 prims. 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 query. 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 prims 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 prims 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]))
Geometry Prim
- class GeometryPrim(prim_path: str, name: str = 'geometry_prim', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, collision: bool = False, track_contact_forces: bool = False, prepare_contact_sensor: bool = False, disable_stablization: bool = True, contact_filter_prim_paths_expr: Optional[List[str]] = [])
High level wrapper to deal with a Geom prim (only one geometry prim) and its attributes/properties.
The
prim_path
should correspond to type UsdGeom.Cube, UsdGeom.Capsule, UsdGeom.Cone, UsdGeom.Cylinder, UsdGeom.Sphere or UsdGeom.Mesh.Warning
The geometry object must be initialized in order to be able to operate on it. See the
initialize
method for more details.Warning
Some methods require the prim to have the Physx Collision API. Instantiate the class with the
collision
parameter to True to apply the collision API.- 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 “xform_prim”.
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.
collision (bool, optional) – Set to True if the geometry should have a collider (i.e not only a visual geometry). Defaults to False.
track_contact_forces (bool, Optional) – if enabled, the view will track the net contact forces on each geometry prim in the view. Note that the collision flag should be set to True to report contact forces. Defaults to False.
prepare_contact_sensors (bool, Optional) – applies contact reporter API to the prim if it already does not have one. Defaults to False.
disable_stablization (bool, optional) – disables the contact stabilization parameter in the physics context. Defaults to True.
contact_filter_prim_paths_expr (Optional[List[str]], Optional) – a list of filter expressions which allows for tracking contact forces between the geometry prim and this subset through get_contact_force_matrix().
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.core.prims import GeometryPrim >>> >>> # create a Cube at the given path >>> stage_utils.get_current_stage().DefinePrim("/World/Xform", "Xform") >>> stage_utils.get_current_stage().DefinePrim("/World/Xform/Cube", "Cube") >>> >>> # wrap the prim as geometry prim >>> prim = GeometryPrim("/World/Xform", collision=True) >>> prim <omni.isaac.core.prims.geometry_prim.GeometryPrim object at 0x7fe960247400>
- 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 ... ) >>> prim.apply_physics_material(material)
- 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)
- property geom: pxr.UsdGeom.Gprim
Returns: UsdGeom.Gprim: USD geometry object encapsulated.
- get_applied_physics_material() omni.isaac.core.materials.physics_material.PhysicsMaterial
Return the current applied physics material in case it was applied using apply_physics_material or not.
- Returns
the current applied physics material.
- Return type
Example:
>>> # given a physics material applied >>> prim.get_applied_physics_material() <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7fb66c30cd30>
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_collision_approximation() str
Get the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Returns
approximation used for collision
- Return type
str
Example:
>>> prim.get_collision_approximation() none
- get_collision_enabled() bool
Check if the Collision API is enabled
- Returns
True if the Collision API is enabled. Otherwise False
- Return type
bool
Example:
>>> prim.get_collision_enabled() True
- get_contact_force_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed contact forces between the prims in the view and the filter prims including the normal contact forces, normal directions, contact points, separations. The number of contacts per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (self._geometry_prim_view._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_contact_offset() float
Get the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
contact offset of the collision shape. Default value is -inf, means default is picked by simulation.
- Return type
float
Example:
>>> prim.get_contact_offset() -inf
- 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
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_friction_data(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If the object is initialized with filter_paths_expr list, this method returns the detailed friction forces between the prims in the view and the filter prims including the tangential forces, and points. The number of points per pair is determined from a static tensor of dimension (self._contact_view.num_filters) while the starting index of the associated contact in the above tensors is determined from another static tensor of dimension (self._contact_view.num_filters).
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), as well as two tensors with shape (self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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_min_torsional_patch_radius() float
Get the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_min_torsional_patch_radius() 0.0
- get_net_contact_forces(dt: float = 1.0) Union[numpy.ndarray, torch.Tensor]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (1, 3)
- Parameters
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (3).
- Return type
Union[np.ndarray, torch.Tensor]
- get_rest_offset() float
Get the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
- Returns
rest offset of the collision shape.
- Return type
float
Example:
>>> prim.get_rest_offset() -inf
- get_torsional_patch_radius() float
Get the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Returns
radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
- Return type
float
Example:
>>> prim.get_torsional_patch_radius() 0.0
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_collision_approximation(approximation_type: str) None
Set the collision approximation
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
Note
Use Convex Decomposition or SDF (Signed-Distance-Field) tri-meshes to capture details better
Warning
Switching to Convex Decomposition or SDF (Signed-Distance-Field) will have a simulation performance impact due to higher computational cost
- Parameters
approximation_type (str) – approximation used for collision
Example:
>>> prim.set_collision_approximation("convexDecomposition")
- set_collision_enabled(enabled: bool) None
Enable/disable the Collision API
- Parameters
enabled (bool) – Whether to enable or disable the Collision API
Example:
>>> # disable collisions >>> prim.set_collision_enabled(False)
- set_contact_offset(offset: float) None
Set the contact offset
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Contact offset of a collision shape. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent.
Example:
>>> prim.set_contact_offset(0.02)
- 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_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_min_torsional_patch_radius(radius: float) None
Set the minimum radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_min_torsional_patch_radius(0.05)
- set_rest_offset(offset: float) None
Set the rest offset
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offset (float) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset. Default value is -inf, means default is picked by simulation. For rigid bodies its zero.
Example:
>>> prim.set_rest_offset(0.01)
- set_torsional_patch_radius(radius: float) None
Set the radius of the contact patch used to apply torsional friction
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radius (float) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float].
Example:
>>> prim.set_torsional_patch_radius(0.1)
- 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.]))
Geometry Prim View
- class GeometryPrimView(prim_paths_expr: str, name: str = 'geometry_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, collisions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, track_contact_forces: bool = False, prepare_contact_sensors: bool = False, disable_stablization: bool = True, contact_filter_prim_paths_expr: Optional[List[str]] = [], max_contact_count: int = 0)
High level wrapper to deal with geom prims (one or many) as well as their attributes/properties.
This class wraps all matching geom prims found at the regex provided at the
prim_paths_expr
argumentNote
Each prim will have
xformOp:orient
,xformOp:translate
andxformOp:scale
only post-init, unless it is a non-root articulation link.Warning
The geometry prim view object must be initialized in order to be able to operate on it. See the
initialize
method for more details.Warning
Some methods require the prims to have the Physx Collision API. Instantiate the class with the
collision
parameter to a list of True values to apply the collision API.- Parameters
prim_paths_expr (str) – prim paths regex to encapsulate all prims that match it. example: “/World/Env[1-5]/Microwave” will match /World/Env1/Microwave, /World/Env2/Microwave..etc. (a non regex prim path can also be used to encapsulate one XForm).
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 “geometry_prim_view”.
positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default positions in the world frame of the prim. 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 prim (depends if translation or position is specified). quaternion is scalar-first (w, x, y, z). shape is (N, 4). Defaults to None, which means left unchanged.
scales (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – local scales to be applied to the prim’s dimensions. 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.
collisions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – Set to True if the geometry already have/ should have a collider (i.e not only a visual geometry). shape is (N,). Defaults to None.
track_contact_forces (bool, Optional) – if enabled, the view will track the net contact forces on each geometry prim in the view. Note that the collision flag should be set to True to report contact forces. Defaults to False.
prepare_contact_sensors (bool, Optional) – applies contact reporter API to the prim if it already does not have one. Defaults to False.
disable_stablization (bool, optional) – disables the contact stabilization parameter in the physics context. Defaults to True.
contact_filter_prim_paths_expr (Optional[List[str]], Optional) – a list of filter expressions which allows for tracking contact forces between the geometry prim and this subset through get_contact_force_matrix().
max_contact_count (int, optional) – maximum number of contact data to report when detailed contact information is needed
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.cloner import GridCloner >>> from omni.isaac.core.prims import GeometryPrimView >>> from pxr import UsdGeom >>> >>> env_zero_path = "/World/envs/env_0" >>> num_envs = 5 >>> >>> # 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) >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform", "Xform") >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform/Cube", "Cube") >>> env_pos = cloner.clone( ... source_prim_path=env_zero_path, ... prim_paths=cloner.generate_paths("/World/envs/env", num_envs), ... copy_from_source=True ... ) >>> >>> # wrap the prims >>> prims = GeometryPrimView( ... prim_paths_expr="/World/envs/env.*/Xform", ... name="geometry_prim_view", ... collisions=[True] * num_envs ... ) >>> prims <omni.isaac.core.prims.geometry_prim_view.GeometryPrimView object at 0x7f372bb21630>
- apply_collision_apis(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Apply the collision API to prims in the view and update internal variables
- Parameters
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:
>>> # apply the collision API for all prims >>> prims.apply_collision_apis() >>> >>> # apply the collision API for the first, middle and last of the 5 envs >>> prims.apply_collision_apis(indices=np.array([0, 2, 4]))
- apply_physics_materials(physics_materials: Union[omni.isaac.core.materials.physics_material.PhysicsMaterial, List[omni.isaac.core.materials.physics_material.PhysicsMaterial]], weaker_than_descendants: Optional[Union[bool, List[bool]]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Used to apply physics material to prims in the view and optionally its descendants.
- Parameters
physics_materials (Union[PhysicsMaterial, List[PhysicsMaterial]]) – physics materials to be applied to prims in the view. Physics material can be used to define friction, restitution..etc. Note: if a physics material is not defined, the defaults will be used from PhysX. 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 physics materials != length of prims indexed
Exception – length of physics materials != length of weaker descendants arg
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 ... ) >>> >>> # apply the material to all prims >>> prims.apply_physics_materials(material) # or [material] * num_envs >>> >>> # apply the collision API for the first, middle and last of the 5 envs >>> prims.apply_physics_materials(material, 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 count: int
- Returns
Number of prims encapsulated in this view.
- Return type
int
Example:
>>> prims.count 5
- disable_collision(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Disables collision on prims in the view.
- Parameters
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:
>>> # disable the collision API for all prims >>> prims.disable_collision() >>> >>> # disable the collision API for the prims for the first, middle and last of the 5 envs >>> prims.disable_collision(indices=np.array([0, 2, 4]))
- enable_collision(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Enables collision on prims in the view.
- Parameters
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 collision API for all prims >>> prims.enable_collision() >>> >>> # enable the collision API for the prims for the first, middle and last of the 5 envs >>> prims.enable_collision(indices=np.array([0, 2, 4]))
- property geoms: List[pxr.UsdGeom.Gprim]
- Returns
USD geom objects encapsulated.
- Return type
List[UsdGeom.Gprim]
Example:
>>> prims.geoms [UsdGeom.Gprim(Usd.Prim(</World/envs/env_0/Xform>)), UsdGeom.Gprim(Usd.Prim(</World/envs/env_1/Xform>)), UsdGeom.Gprim(Usd.Prim(</World/envs/env_2/Xform>)), UsdGeom.Gprim(Usd.Prim(</World/envs/env_3/Xform>)), UsdGeom.Gprim(Usd.Prim(</World/envs/env_4/Xform>))]
- get_applied_physics_materials(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) List[omni.isaac.core.materials.physics_material.PhysicsMaterial]
Get the applied physics material to 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).
- Returns
the current applied physics materials for prims in the view.
- Return type
List[PhysicsMaterial]
Example:
>>> # get the applied material for all prims >>> prims.get_applied_physics_materials() [<omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>] >>> >>> # get the applied material for the first, middle and last of the 5 envs >>> prims.get_applied_physics_materials(indices=np.array([0, 2, 4])) [<omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>, <omni.isaac.core.materials.physics_material.PhysicsMaterial object at 0x7f720859ece0>]
- 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_collision_approximations(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) List[str]
Get collision approximation types for prims in the view.
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- 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
approximations used for collision. size == M or size of the view.
- Return type
List[str]
Example:
>>> # get the collision approximation of all prims. Returned size is (5,). >>> prims.get_collision_approximations() ['none', 'none', 'none', 'none', 'none'] >>> >>> # get the collision approximation of the prims for the first, middle and last of the 5 envs >>> prims.get_collision_approximations(indices=np.array([0, 2, 4])) ['none', 'none', 'none']
- get_contact_force_data(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Get more detailed contact information between the prims in the view and the filter prims. Specifically, this method provides individual contact normals, contact points, contact separations as well as contact forces for each pair (the sum of which equals the forces that the get_contact_force_matrix method provides as the force aggregate of a pair) Given to the dynamic nature of collision between bodies, this method will provide buffers of contact data which are arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of (self.num_shapes, self.num_filters) where filter_count is determined according to the filter_paths_expr parameter.
- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
- Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray],
Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_contact_force_matrix(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
If the object is initialized with filter_paths_expr list, this method returns the contact forces between the prims in the view and the filter prims. i.e., a matrix of dimension (self.count, self._contact_view.num_filters, 3) where num_filters is the determined according to the filter_paths_expr parameter.
- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (M, self._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
- get_contact_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get contact offsets for prims in the view.
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection 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
Contact offsets of the collision shapes. Shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the contact offsets of all prims. Returned shape is (5,). >>> prims.get_contact_offsets() [-inf -inf -inf -inf -inf] >>> >>> # get the contact offsets of the prims for the first, middle and last of the 5 envs >>> prims.get_contact_offsets(indices=np.array([0, 2, 4])) [-inf -inf -inf]
- 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
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_friction_data(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Gets friction data between the prims in the view and the filter prims. Specifically, this method provides frictional contact forces, and points. The data in reported for number of anchor points that includes tangential forces in a single tangent direction to contact normal. Given to the dynamic nature of collision between bodies, this method will provide buffers of friction data arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of (self.num_shapes, self.num_filters) where filter_count is determined according to the filter_paths_expr parameter.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indicies 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
- Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray],
Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for tangential forces per patch (at number of anchor points, each in a single directions) with shape (max_contact_count, 3), points with shape (max_contact_count, 3), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- 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 translations 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 prims 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 [[ 1.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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 [[ 1.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> 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_min_torsional_patch_radii(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
Get minimum torsional patch radii for prims in the view.
Search for “Torsional Patch Radius” in PhysX docs for more details
- 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
minimum radius of the contact patch used to apply torsional friction. shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor]
Example:
>>> # get the minimum torsional patch radius of all prims. Returned shape is (5,). >>> prims.get_min_torsional_patch_radii() [0. 0. 0. 0. 0.] >>> >>> # get the minimum torsional patch radius of the prims for the first, middle and last of the 5 envs >>> prims.get_min_torsional_patch_radii(indices=np.array([0, 2, 4])) [0. 0. 0.]
- get_net_contact_forces(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
If contact forces of the prims in the view are tracked, this method returns the net contact forces on prims. i.e., a matrix of dimension (self.count, 3)
- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (M,3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
- get_rest_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get rest offsets for prims in the view.
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection 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
Rest offsets of the collision shapes. Shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the rest offsets of all prims. Returned shape is (5,). >>> prims.get_rest_offsets() [-inf -inf -inf -inf -inf] >>> >>> # get the rest offsets of the prims for the first, middle and last of the 5 envs >>> prims.get_rest_offsets(indices=np.array([0, 2, 4])) [-inf -inf -inf]
- get_torsional_patch_radii(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get torsional patch radii for prims in the view.
Search for “Torsional Patch Radius” 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
radius of the contact patch used to apply torsional friction. shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the torsional patch radius of all prims. Returned shape is (5,). >>> prims.get_torsional_patch_radii() [0. 0. 0. 0. 0.] >>> >>> # get the torsional patch radius of the prims for the first, middle and last of the 5 envs >>> prims.get_torsional_patch_radii(indices=np.array([0, 2, 4])) [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, 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).
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 prims 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.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> 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 rigid prim 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()
- is_collision_enabled(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Queries if collision is enabled on 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).
- Returns
True if collision is enabled. Shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # check if the collision is enabled for all prims. Returned size is (5,). >>> prims.is_collision_enabled() [ True True True True True] >>> >>> # check if the collision is enabled for the first, middle and last of the 5 envs >>> prims.is_collision_enabled(indices=np.array([0, 2, 4])) [ True True True]
- property is_non_root_articulation_link: bool
Returns: bool: True if the prim corresponds to a non root link in an articulation. Otherwise False.
- 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 name: str
Returns: str: name given to the prims view when instantiating it.
- post_reset() None
Reset the prims to its default state (positions and orientations)
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>)]
- set_collision_approximations(approximation_types: List[str], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set collision approximation types for prims in the view.
Approximation
Full name
Description
"none"
Triangle Mesh
The mesh geometry is used directly as a collider without any approximation
"convexDecomposition"
Convex Decomposition
A convex mesh decomposition is performed. This results in a set of convex mesh colliders
"convexHull"
Convex Hull
A convex hull of the mesh is generated and used as the collider
"boundingSphere"
Bounding Sphere
A bounding sphere is computed around the mesh and used as a collider
"boundingCube"
Bounding Cube
An optimally fitting box collider is computed around the mesh
"meshSimplification"
Mesh Simplification
A mesh simplification step is performed, resulting in a simplified triangle mesh collider
"sdf"
SDF Mesh
SDF (Signed-Distance-Field) use high-detail triangle meshes as collision shape
"sphereFill"
Sphere Approximation
A sphere mesh decomposition is performed. This results in a set of sphere colliders
- Parameters
approximation_types (List[str]) – approximations used for collision. List size == M or the size of the view.
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 collision approximations for all the prims to the specified values. >>> prims.set_collision_approximations(["convexDecomposition"] * num_envs) >>> >>> # set the collision approximations for the first, middle and last of the 5 envs >>> types = ["convexDecomposition", "convexHull", "meshSimplification"] >>> prims.set_collision_approximations(types, indices=np.array([0, 2, 4]))
- set_contact_offsets(offsets: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set contact offsets for prims in the view.
Shapes whose distance is less than the sum of their contact offset values will generate contacts
Search for Advanced Collision Detection in PhysX docs for more details
- Parameters
offsets (Union[np.ndarray, torch.Tensor, wp.array]) – Contact offsets of the collision shapes. Allowed range [maximum(0, rest_offset), 0]. Default value is -inf, means default is picked by simulation based on the shape extent. 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 contact offset for all the prims to the specified values. >>> prims.set_contact_offsets(np.full(num_envs, 0.02)) >>> >>> # set the contact offset for the first, middle and last of the 5 envs >>> prims.set_contact_offsets(np.full(3, 0.02), indices=np.array([0, 2, 4]))
- 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()
orworld.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_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 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_local_poses(positions, orientations) >>> >>> # reposition only the prims 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_min_torsional_patch_radii(radii: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set minimum torsional patch radii for prims in the view.
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radii (Union[np.ndarray, torch.Tensor, wp.array]) – minimum radius of the contact patch used to apply torsional friction. Allowed range [0, max_float]. shape is (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 minimum torsional patch radius for all the prims to the specified values. >>> prims.set_min_torsional_patch_radii(np.full(num_envs, 0.05)) >>> >>> # set the minimum torsional patch radius for the first, middle and last of the 5 envs >>> prims.set_min_torsional_patch_radii(np.full(3, 0.05), indices=np.array([0, 2, 4]))
- set_rest_offsets(offsets: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set rest offsets for prims in the view.
Two shapes will come to rest at a distance equal to the sum of their rest offset values. If the rest offset is 0, they should converge to touching exactly
Search for Advanced Collision Detection in PhysX docs for more details
Warning
The contact offset must be positive and greater than the rest offset
- Parameters
offsets (Union[np.ndarray, torch.Tensor, wp.array]) – Rest offset of a collision shape. Allowed range [-max_float, contact_offset]. Default value is -inf, means default is picked by simulation. For rigid bodies its zero. 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 rest offset for all the prims to the specified values. >>> prims.set_rest_offsets(np.full(num_envs, 0.01)) >>> >>> # set the rest offset for the first, middle and last of the 5 envs >>> prims.set_rest_offsets(np.full(3, 0.01), indices=np.array([0, 2, 4]))
- set_torsional_patch_radii(radii: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set torsional patch radii for prims in the view.
Search for “Torsional Patch Radius” in PhysX docs for more details
- Parameters
radii (Union[np.ndarray, torch.Tensor, wp.array]) – radius of the contact patch used to apply torsional friction. Allowed range [0, max_float]. shape is (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 torsional patch radius for all the prims to the specified values. >>> prims.set_torsional_patch_radii(np.full(num_envs, 0.1)) >>> >>> # set the torsional patch radius for the first, middle and last of the 5 envs >>> prims.set_torsional_patch_radii(np.full(3, 0.1), 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 prim poses 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 prims. 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 query. 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 prims 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 prims 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]))
Rigid Prim
- class RigidPrim(prim_path: str, name: str = 'rigid_prim', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, mass: Optional[float] = None, density: Optional[float] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None)
High level wrapper to deal with a rigid body prim (only one rigid body prim) and its attributes/properties.
Warning
The rigid body object must be initialized in order to be able to operate on it. See the
initialize
method for more details.Note
If the prim does not already have the Rigid Body API applied to it before init, it will apply it.
- 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 “rigid_prim”.
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.
mass (Optional[float], optional) – mass in kg. Defaults to None.
density (Optional[float], optional) – density. Defaults to None.
linear_velocity (Optional[np.ndarray], optional) – linear velocity in the world frame. Defaults to None.
angular_velocity (Optional[np.ndarray], optional) – angular velocity in the world frame. Defaults to None.
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.core.prims import RigidPrim >>> >>> # create a Cube at the given path >>> stage_utils.get_current_stage().DefinePrim("/World/Xform", "Xform") >>> stage_utils.get_current_stage().DefinePrim("/World/Xform/Cube", "Cube") >>> >>> # wrap the prim as rigid prim >>> prim = RigidPrim("/World/Xform") >>> prim <omni.isaac.core.prims.rigid_prim.RigidPrim object at 0x7fc4a7f56e90>
- 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_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- get_angular_velocity()
Get the angular velocity of the rigid body
- Returns
current angular velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- get_default_state() omni.isaac.core.utils.types.DynamicState
Get the default rigid body state (position, orientation and linear and angular velocities)
- Returns
returns the default state of the prim that is used after each reset
- Return type
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f7411fcbe20> >>> state.position [-7.8622378e-07 1.4450421e-06 1.6135601e-07] >>> state.orientation [ 9.9999994e-01 -2.7194994e-07 2.9607077e-07 2.7016510e-08] >>> state.linear_velocity [0. 0. 0.] >>> state.angular_velocity [0. 0. 0.]
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- 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_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Returns
- Mass-normalized kinetic energy threshold below which
an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
- Return type
float
Example:
>>> prim.get_sleep_threshold() 5e-05
- 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.]
- 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:
>>> 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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 rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, linear_velocity: Optional[numpy.ndarray] = None, angular_velocity: Optional[numpy.ndarray] = None) None
Set the default state of the prim (position, orientation and linear and angular velocities), that will be used after each reset
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- 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.
linear_velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
angular_velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
Example:
>>> prim.set_default_state( ... position=np.array([1.0, 2.0, 3.0]), ... orientation=np.array([1.0, 0.0, 0.0, 0.0]), ... linear_velocity=np.array([0.0, 0.0, 0.0]), ... angular_velocity=np.array([0.0, 0.0, 0.0]) ... ) >>> >>> prim.post_reset()
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- 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_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None
Set the visibility of the prim in stage
- Parameters
visible (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.]))
Rigid Prim View
- class RigidPrimView(prim_paths_expr: Union[str, List[str]], name: str = 'rigid_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, masses: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, densities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, linear_velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, angular_velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, track_contact_forces: bool = False, prepare_contact_sensors: bool = True, disable_stablization: bool = True, contact_filter_prim_paths_expr: Optional[List[str]] = [], max_contact_count: int = 0)
Provides high level functions to deal with prims (one or many) that have Rigid Body API applied to them as well as their attributes/properties.
This class wraps all matching rigid prims found at the regex provided at the
prim_paths_expr
argumentNote
Each prim will have
xformOp:orient
,xformOp:translate
andxformOp:scale
only post-init, unless it is a non-root articulation link.If the prims do not already have the Rigid Body API applied to them before init, it will apply it.
Warning
The rigid prim 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]/Cube” will match /World/Env1/Cube, /World/Env2/Cube..etc. (a non regex prim path can also be used to encapsulate one rigid prim). Additionally a list of regex can be provided. example [“/World/Env[1-5]/Cube”, “/World/Env[10-19]/Cube”].
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 “rigid_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). Defaults to None, which means left unchanged.
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.
masses (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – mass in kg specified for each prim in the view. shape is (N,). Defaults to None.
densities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – density in kg/m^3 specified for each prim in the view. shape is (N,). Defaults to None.
linear_velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default linear velocity of each prim in the view (to be applied in the first frame and on resets). Shape is (N, 3). Defaults to None.
angular_velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default angular velocity of each prim in the view (to be applied in the first frame and on resets). Shape is (N, 3). Defaults to None.
track_contact_forces (bool, Optional) – if enabled, the view will track the net contact forces on each rigid prim in the view
prepare_contact_sensors (bool, Optional) – if rigid prims in the view are not cloned from a prim in a prepared state, (although slow for large number of prims) this ensures that appropriate physics settings are applied on all the prim in the view.
disable_stablization (bool, optional) – disables the contact stabilization parameter in the physics context
contact_filter_prim_paths_expr (Optional[List[str]], Optional) – a list of filter expressions which allows for tracking contact forces between prims and this subset through get_contact_force_matrix().
max_contact_count (int, optional) – maximum number of contact data to report when detailed contact information is needed
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.cloner import GridCloner >>> from omni.isaac.core.prims import RigidPrimView >>> from pxr import UsdGeom >>> >>> env_zero_path = "/World/envs/env_0" >>> num_envs = 5 >>> >>> # 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) >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform", "Xform") >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform/Cube", "Cube") >>> env_pos = cloner.clone( ... source_prim_path=env_zero_path, ... prim_paths=cloner.generate_paths("/World/envs/env", num_envs), ... copy_from_source=True ... ) >>> >>> # wrap the prims >>> prims = RigidPrimView(prim_paths_expr="/World/envs/env.*/Xform", name="rigid_prim_view") >>> prims <omni.isaac.core.prims.rigid_prim_view.RigidPrimView object at 0x7f9a23b8bb80>
- apply_forces(forces: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, is_global: bool = True) None
Applies forces to prims in the view.
- Parameters
forces (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – forces to be applied to the prims.
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).
is_global (bool, optional) – True if forces are in the global frame. Otherwise False. Defaults to True.
Example:
>>> # apply an external force to all the rigid bodies to the indicated values. >>> # Since there are 5 envs, the inertias are repeated 5 times >>> forces = np.tile(np.array([2e5, 1e5, 0.0]), (num_envs, 1)) >>> prims.apply_forces(forces) >>> >>> # apply an external force to the rigid bodies for the first, middle and last of the 5 envs >>> forces = np.tile(np.array([2e5, 1e5, 0.0]), (3, 1)) >>> prims.apply_forces(forces, indices=np.array([0, 2, 4]))
- apply_forces_and_torques_at_pos(forces: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, torques: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, positions: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, is_global: bool = True) None
Applies forces and torques to prims in the view. The forces and/or torques can be in local or global coordinates. The forces can applied at a location given by positions variable.
- Parameters
forces (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – forces to be applied to the prims. If not specified, no force will be applied. Defaults to None (i.e: no forces will be applied).
torques (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – torques to be applied to the prims. If not specified, no torque will be applied. Defaults to None (i.e: no torques will be applied).
positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – position of the forces with respect to the body frame. If not specified, the forces are applied at the origin of the body frame. Defaults to None (i.e: applied forces will be at the origin of the body frame).
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).
is_global (bool, optional) – True if forces, torques, and positions are in the global frame. False if forces, torques, and positions are in the local frame. Defaults to True.
Example:
>>> # apply an external force and torque to all the rigid bodies to the indicated values. >>> # Since there are 5 envs, the inertias are repeated 5 times >>> forces = np.tile(np.array([2e5, 1e5, 0.0]), (num_envs, 1)) >>> torques = np.tile(np.array([2e5, 1e5, 0.0]), (num_envs, 1)) >>> prims.apply_forces_and_torques_at_pos(forces, torques) >>> >>> # apply an external force and torque to the rigid bodies for the first, middle and last of the 5 envs >>> forces = np.tile(np.array([2e5, 1e5, 0.0]), (3, 1)) >>> torques = np.tile(np.array([2e5, 1e5, 0.0]), (3, 1)) >>> prims.apply_forces_and_torques_at_pos(forces, torques, 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 count: int
- Returns
Number of prims encapsulated in this view.
- Return type
int
Example:
>>> prims.count 5
- disable_gravities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Disable gravity on rigid bodies (enabled by default).
- Parameters
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:
>>> # disable the gravity for all rigid bodies >>> prims.disable_gravities() >>> >>> # disable the rigid body gravity for the first, middle and last of the 5 envs >>> prims.disable_gravities(indices=np.array([0, 2, 4]))
- disable_rigid_body_physics(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Disable rigid body physics (enabled by default)
When disabled, the objects will not be moved by external forces such as gravity and collisions
- Parameters
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 rigid body dynamics for all rigid bodies >>> prims.disable_rigid_body_physics() >>> >>> # enable the rigid body dynamics for the first, middle and last of the 5 envs >>> prims.disable_rigid_body_physics(indices=np.array([0, 2, 4]))
- enable_gravities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Enable gravity on rigid bodies (enabled by default).
- Parameters
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 gravity for all rigid bodies >>> prims.enable_gravities() >>> >>> # enable the rigid body gravity for the first, middle and last of the 5 envs >>> prims.enable_gravities(indices=np.array([0, 2, 4]))
- enable_rigid_body_physics(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Enable rigid body physics (enabled by default)
When enabled, the objects will be moved by external forces such as gravity and collisions
- Parameters
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 rigid body dynamics for all rigid bodies >>> prims.enable_rigid_body_physics() >>> >>> # enable the rigid body dynamics for the first, middle and last of the 5 envs >>> prims.enable_rigid_body_physics(indices=np.array([0, 2, 4]))
- 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 rigid prim 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 rigid prim 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_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_coms(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 bodies 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
rigid body center of mass positions and orientations of prims in the view. position shape is (M, 1, 3), orientation shape is (M, 1, 4).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body center of mass. >>> # Returned shape is (5, 1, 3) for positions and (5, 1, 4) for orientations for the example: 5 envs >>> positions, orientations = prims.get_coms() >>> positions [[[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.]]] >>> >>> # get rigid body center of mass for the first, middle and last of the 5 envs. >>> # Returned shape is (3, 1, 3) for positions and (3, 1, 4) for orientations >>> positions, orientations = prims.get_coms(indices=np.array([0, 2, 4])) >>> positions [[[0. 0. 0.]] [[0. 0. 0.]] [[0. 0. 0.]]] >>> orientations [[[1. 0. 0. 0.]] [[1. 0. 0. 0.]] [[1. 0. 0. 0.]]]
- get_contact_force_data(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Get more detailed contact information between the prims in the view and the filter prims.
Specifically, this method provides individual contact normals, contact points, contact separations as well as contact forces for each pair (the sum of which equals the forces that the
get_contact_force_matrix
method provides as the force aggregate of a pair)Given to the dynamic nature of collision between bodies, this method will provide buffers of contact data which are arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of
(num_shapes, _contact_view.num_filters)
where_contact_view.num_filters
is determined according to thecontact_filter_prim_paths_expr
parameterNote
This method requires that the contact forces of the prims in the view be tracked by defining the
contact_filter_prim_paths_expr
argument to a list of the prim paths from which to generate the information and themax_contact_count
argument be greater than 0 during view creation- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
Example:
>>> # for the example, the cubes are on top of each other. The view was instantiated with the following >>> # extra parameters: contact_filter_prim_paths_expr=["/World/envs/env_2/Xform"], max_contact_count=10 >>> # This indicates that only contacts with the middle cube will be reported >>> data = prims.get_contact_force_data() >>> data[0] # normal forces [[-156.449 ] [ -81.736336] [-169.73076 ] [ -82.397804] [ 110.11985 ] [ 59.646057] [ 98.660545] [ 58.43006 ] [ 0. ] [ 0. ]] >>> data[1] # points [[-0.50145745 0.49872556 0.7056795 ] [-0.50184476 -0.5010655 0.7057198 ] [ 0.49793154 -0.50147027 0.70576656] [ 0.4983363 0.49833822 0.70572615] [ 0.49818155 -0.5016888 1.7058725 ] [ 0.49856627 0.4913648 1.7058672 ] [-0.49732465 0.4915302 1.705814 ] [-0.49748957 -0.501303 1.7058194 ] [ 0. 0. 0. ] [ 0. 0. 0. ]] >>> data[2] # normals [[ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 1.6479074e-05 -1.6995813e-05 1.0000000e+00] [ 0.0000000e+00 0.0000000e+00 0.0000000e+00] [ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] >>> data[3] # distances [[ 6.3175990e-05] [ 5.8271162e-06] [-5.7399273e-05] [-1.0989098e-08] [ 1.6338757e-04] [ 1.4112510e-04] [ 7.1585178e-05] [ 9.3835908e-05] [ 0.0000000e+00] [ 0.0000000e+00]] >>> data[4] # pair contacts count [[0] [4] [0] [4] [0]] >>> data[5] # start indices of pair contacts [[0] [0] [4] [4] [8]]
- get_contact_force_matrix(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Return the contact forces between the prims in the view and the filter prims
E.g., a matrix of dimension
(self.count, _contact_view.num_filters, 3)
where_contact_view.num_filters
is determined according to thecontact_filter_prim_paths_expr
parameterNote
This method requires that the contact forces of the prims in the view be tracked by defining the
contact_filter_prim_paths_expr
argument to a list of the prim paths from which to generate the information and themax_contact_count
argument be greater than 0 during view creation- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (M, self._contact_view.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # for the example, the cubes are on top of each other. The view was instantiated with the following >>> # extra parameters: contact_filter_prim_paths_expr=["/World/envs/env_2/Xform"], max_contact_count=10 >>> # This indicates that only contacts with the middle cube will be reported >>> prims.get_contact_force_matrix() [[[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] [[-7.8665102e-03 8.3034458e-03 -4.9063504e+02]] [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] [[ 5.2445102e-03 -5.5358098e-03 3.2710065e+02]] [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]]]
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicsViewState
Get the current rigid body states (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid bodies
- Return type
Example:
>>> # for the example the rigid bodies are in free fall >>> state = prims.get_default_state() <omni.isaac.core.utils.types.DynamicsViewState object at 0x7f182bd72590> >>> state >>> state.positions [[ 1.5 -0.75 -207.76808] [ 1.5 0.75 -207.76808] [ 0. -0.75 -207.76808] [ 0. 0.75 -207.76808] [ -1.5 -0.75 -207.76808]] >>> state.orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> state.linear_velocities [[ 0. 0. -63.765312] [ 0. 0. -63.765312] [ 0. 0. -63.765312] [ 0. 0. -63.765312] [ 0. 0. -63.765312]] >>> state.angular_velocities [[0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.]]
- get_default_state() omni.isaac.core.utils.types.DynamicsViewState
Get the default state (position, orientation and linear and angular velocities) of prims in the view, that will be used after each reset.
- Returns
returns the default state of the prims that is used after each reset.
- Return type
Example:
>>> state = prims.get_default_state() <omni.isaac.core.utils.types.DynamicsViewState object at 0x7f184e555480> >>> state >>> state.positions [[ 1.4999989e+00 -7.4999851e-01 -1.5118626e-07] [ 1.4999989e+00 7.5000149e-01 -2.5988294e-07] [-1.0017333e-06 -7.4999845e-01 7.6070329e-08] [-9.5906785e-07 7.5000149e-01 1.0593490e-07] [-1.5000011e+00 -7.4999851e-01 1.9655154e-07]] >>> state.orientations [[ 9.9999994e-01 -8.8168377e-07 -4.1946004e-07 -1.5067183e-08] [ 9.9999994e-01 -8.8691013e-07 -4.2665880e-07 -2.7188951e-09] [ 1.0000000e+00 -9.5171310e-07 -2.2615541e-07 5.5922797e-08] [ 1.0000000e+00 -8.9923367e-07 -1.4408238e-07 1.3476099e-08] [ 1.0000000e+00 -7.9806580e-07 -1.3064776e-07 5.3154917e-08]] >>> state.linear_velocities [[0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.]] >>> state.angular_velocities [[0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.] [0. 0. 0.]]
- get_densities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get densities 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)
- Returns
densities of prims in the view in kg/m^3. shape (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body densities. Returned shape is (5,) for the example: 5 envs >>> prims.get_densities() [0. 0. 0. 0. 0.] >>> >>> # get rigid body densities for the first, middle and last of the 5 envs. Returned shape is (3,) >>> prims.get_densities(indices=np.array([0, 2, 4])) [0. 0. 0.]
- get_friction_data(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Gets friction data between the prims in the view and the filter prims. Specifically, this method provides frictional contact forces, and points. The data in reported for number of anchor points that includes tangential forces in a single tangent direction to contact normal. Given to the dynamic nature of collision between bodies, this method will provide buffers of friction data arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of (self.num_shapes, self.num_filters) where filter_count is determined according to the filter_paths_expr parameter.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indicies 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
- Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray],
Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for tangential forces per patch (at number of anchor points, each in a single directions) with shape (max_contact_count, 3), points with shape (max_contact_count, 3), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_inertias(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 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
rigid body inertias of prims in the view. Shape is (M, 9).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body inertias. Returned shape is (5, 9) for the example: 5 envs >>> prims.get_inertias() [[166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667]] >>> >>> # get rigid body inertias for the first, middle and last of the 5 envs. Returned shape is (3, 9) >>> prims.get_inertias(indices=np.array([0, 2, 4])) [[166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667] [166.66667 0. 0. 0. 166.66667 0. 0. 0. 166.66667]]
- get_inv_inertias(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 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
rigid body inverse inertias of prims in the view. Shape is (M, 9).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body inverse inertias. Returned shape is (5, 9) for the example: 5 envs >>> prims.get_inv_inertias() [[0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006]] >>> >>> # get rigid body inverse inertias for the first, middle and last of the 5 envs. Returned shape is (3, 9) >>> prims.get_inv_inertias(indices=np.array([0, 2, 4])) [[0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006] [0.006 0. 0. 0. 0.006 0. 0. 0. 0.006]]
- get_inv_masses(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 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
rigid body inverse masses of prims in the view. Shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body inverse masses. Returned shape is (5, 1) for the example: 5 envs >>> prims.get_inv_masses() [[0.001] [0.001] [0.001] [0.001] [0.001]] >>> >>> # get rigid body inverse masses for the first, middle and last of the 5 envs. Returned shape is (3, 1) >>> prims.get_inv_masses(indices=np.array([0, 2, 4])) [[0.001] [0.001] [0.001]]
- get_linear_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 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 rigid prim 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 rigid prim 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_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 rigid prim 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 [[-1.0728836e-06 1.4901161e-06 -1.5118626e-07] [-1.0728836e-06 1.4901161e-06 -2.5988294e-07] [-1.0017333e-06 1.5497208e-06 7.6070329e-08] [-9.5906785e-07 1.4901161e-06 1.0593490e-07] [-1.0728836e-06 1.4901161e-06 1.9655154e-07]] >>> orientations [[ 1.0000000e+00 -8.8174920e-07 -4.1949116e-07 -1.5068302e-08] [ 1.0000000e+00 -8.8696777e-07 -4.2668654e-07 -2.7190719e-09] [ 1.0000000e+00 -9.5164734e-07 -2.2613979e-07 5.5918935e-08] [ 1.0000000e+00 -8.9923157e-07 -1.4408204e-07 1.3476067e-08] [ 1.0000000e+00 -7.9806864e-07 -1.3064822e-07 5.3155105e-08]] >>> >>> # get only the rigid prim 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 [[-1.0728836e-06 1.4901161e-06 -1.5118626e-07] [-1.0017333e-06 1.5497208e-06 7.6070329e-08] [-1.0728836e-06 1.4901161e-06 1.9655154e-07]] >>> orientations [[ 1.0000000e+00 -8.8174920e-07 -4.1949116e-07 -1.5068302e-08] [ 1.0000000e+00 -9.5164734e-07 -2.2613979e-07 5.5918935e-08] [ 1.0000000e+00 -7.9806864e-07 -1.3064822e-07 5.3155105e-08]]
- 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_masses(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 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
masses of in kg of prims in the view. shape is (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid body masses. Returned shape is (5,) for the example: 5 envs >>> prims.get_masses() [999.99994 999.99994 999.99994 999.99994 999.99994] >>> >>> # get rigid body masses for the first, middle and last of the 5 envs. Returned shape is (3,) >>> prims.get_masses(indices=np.array([0, 2, 4])) [999.99994 999.99994 999.99994]
- get_net_contact_forces(indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Return the net contact forces on prims
Note
This method requires that the contact forces of the prims in the view be tracked by defining the
track_contact_forces
argument to True (default to False) during view creation- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Net contact forces of the prims with shape (M,3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the net contact force on all rigid bodies. Returned shape is (5, 3). >>> # For the example the view was instantiated with the extra parameter: track_contact_forces=True >>> prims.get_net_contact_forces() [[2.1967362e-05 0.0000000e+00 1.6349771e+02] [2.1967124e-05 0.0000000e+00 1.6349591e+02] [2.1967891e-05 0.0000000e+00 1.6350165e+02] [2.1967257e-05 0.0000000e+00 1.6349693e+02] [2.1966895e-05 0.0000000e+00 1.6349425e+02]] >>> >>> # get the net contact force on the rigid bodies for the first, middle and last of the 5 envs >>> prims.get_net_contact_forces(indices=np.array([0, 2, 4])) [[2.1967362e-05 0.0000000e+00 1.6349771e+02] [2.1967891e-05 0.0000000e+00 1.6350165e+02] [2.1966895e-05 0.0000000e+00 1.6349425e+02]]
- get_sleep_thresholds(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get sleep thresholds of prims in the view.
Search for Rigid Body Dynamics > 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
Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf). Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2. shape (M,).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all sleep threshold. Returned shape is (5,) for the example: 5 envs >>> prims.get_sleep_thresholds() [5.e-05 5.e-05 5.e-05 5.e-05 5.e-05] >>> >>> # get sleep threshold for the first, middle and last of the 5 envs. Returned shape is (3,) >>> prims.get_sleep_thresholds(indices=np.array([0, 2, 4])) [5.e-05 5.e-05 5.e-05]
- 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).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get all rigid prim 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 rigid prim 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 rigid prim 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.4999989e+00 -7.4999851e-01 -1.5118626e-07] [ 1.4999989e+00 7.5000149e-01 -2.5988294e-07] [-1.0017333e-06 -7.4999845e-01 7.6070329e-08] [-9.5906785e-07 7.5000149e-01 1.0593490e-07] [-1.5000011e+00 -7.4999851e-01 1.9655154e-07]] >>> orientations [[ 9.9999994e-01 -8.8168377e-07 -4.1946004e-07 -1.5067183e-08] [ 9.9999994e-01 -8.8691013e-07 -4.2665880e-07 -2.7188951e-09] [ 1.0000000e+00 -9.5171310e-07 -2.2615541e-07 5.5922797e-08] [ 1.0000000e+00 -8.9923367e-07 -1.4408238e-07 1.3476099e-08] [ 1.0000000e+00 -7.9806580e-07 -1.3064776e-07 5.3154917e-08]] >>> >>> # get only the rigid prim 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.4999989e+00 -7.4999851e-01 -1.5118626e-07] [-1.0017333e-06 -7.4999845e-01 7.6070329e-08] [-1.5000011e+00 -7.4999851e-01 1.9655154e-07]] >>> orientations [[ 9.9999994e-01 -8.8168377e-07 -4.1946004e-07 -1.5067183e-08] [ 1.0000000e+00 -9.5171310e-07 -2.2615541e-07 5.5922797e-08] [ 1.0000000e+00 -7.9806580e-07 -1.3064776e-07 5.3154917e-08]]
- 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 rigid prim 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 is_non_root_articulation_link: bool
Returns: bool: True if the prim corresponds to a non root link in an articulation. Otherwise False.
- is_physics_handle_valid() bool
Check if rigid prim 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
True if the physics handle of the view is valid (i.e physics is initialized for the view). Otherwise False.
- 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 name: str
Returns: str: name given to the prims view when instantiating it.
- property num_shapes: int
- Returns
number of rigid shapes for the prims in the view.
- Return type
int
Example:
>>> prims.num_shapes 1
- post_reset() None
Reset the rigid prims to their default states (positions, orientations and linear and angular velocities)
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>)]
- set_angular_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], 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 rigid prim 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 rigid prim kinematic state:
set_velocities
(set_linear_velocities
,set_angular_velocities
)Example:
>>> # set each rigid prim linear velocity to (5.0, 5.0, 5.0) >>> velocities = np.full((num_envs, 3), fill_value=5.0) >>> prims.set_angular_velocities(velocities) >>> >>> # set only the rigid prim linear velocities for the first, middle and last of the 5 envs >>> velocities = np.full((3, 3), fill_value=5.0) >>> prims.set_angular_velocities(velocities, indices=np.array([0, 2, 4]))
- set_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) None
Set body center of mass (COM) positions and orientations for bodies in the view.
- Parameters
positions (Union[np.ndarray, torch.Tensor, wp.array]) – body center of mass positions for bodies in the view. shape (M, 1, 3).
orientations (Union[np.ndarray, torch.Tensor, wp.array]) – body center of mass orientations for bodies in the view. shape (M, 1, 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).
Example:
>>> # set the center of mass for all the rigid bodies to the specified 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, 1, 1)) >>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (num_envs, 1, 1)) >>> prims.set_coms(positions, orientations) >>> >>> # set the rigid bodies center of mass for the first, middle and last of the 5 envs >>> positions = np.tile(np.array([0.01, 0.02, 0.03]), (3, 1, 1)) >>> orientations = np.tile(np.array([1.0, 0.0, 0.0, 0.0]), (3, 1, 1)) >>> prims.set_coms(positions, orientations, indices=np.array([0, 2, 4]))
- 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, linear_velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, angular_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 default state (position, orientation and linear and angular velocities) of prims in the view, that will be used after each reset.
Note
The default states will be set during post-reset (e.g., calling
.post_reset()
orworld.reset()
methods)- Parameters
positions (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default positions in the world frame of the prim. shape is (M, 3).
orientations (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default quaternion orientations in the world frame of the prims. quaternion is scalar-first (w, x, y, z). shape is (M, 4).
linear_velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default linear velocities of each prim in the view (to be applied in the first frame and on resets). Shape is (M, 3). Defaults to None.
angular_velocities (Optional[Union[np.ndarray, torch.Tensor, wp.array]], optional) – default angular velocities of each prim in the view (to be applied in the first frame and on resets). Shape is (M, 3). 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).
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)) >>> linear_velocities = np.zeros((num_envs, 3)) >>> angular_velocities = np.zeros((num_envs, 3)) >>> prims.set_default_state( ... positions=positions, ... orientations=orientations, ... linear_velocities=linear_velocities, ... angular_velocities=angular_velocities ... ) >>> >>> # set default states during post-reset >>> prims.post_reset()
- set_densities(densities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set densities of prims in the view.
- Parameters
densities (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – density in kg/m^3 specified for each prim in the view. shape is (M,). 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).
Example:
>>> # set all rigid body densities to the specified values >>> prims.set_densities(np.full(num_envs, 0.9)) >>> >>> # set rigid body densities for the first, middle and last of the 5 envs >>> prims.set_densities(np.full(3, 0.9), indices=np.array([0, 2, 4]))
- set_inertias(values: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None
Set rigid body inertias for prims in the view.
- Parameters
values (Union[np.ndarray, torch.Tensor, wp.array]) – body inertias for prims in the view. shape (M, 1, 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).
Example:
>>> # set the rigid body inertias for all the rigid bodies to the specified 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, 1)) >>> prims.set_inertias(inertias) >>> >>> # set the rigid body inertias 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, 1)) >>> prims.set_inertias(inertias, indices=np.array([0, 2, 4]))
- set_linear_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = 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 rigid prim 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 rigid prim kinematic state:
set_velocities
(set_linear_velocities
,set_angular_velocities
)Example:
>>> # set each rigid prim linear velocity to (1.0, 1.0, 1.0) >>> velocities = np.ones((num_envs, 3)) >>> prims.set_linear_velocities(velocities) >>> >>> # set only the rigid prim 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).
- 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).
Example:
>>> # reposition all rigid 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_local_poses(positions, orientations) >>> >>> # reposition only the rigid prims 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_masses(masses: Union[numpy.ndarray, torch.Tensor, warp.types.array], indices: Optional[Union[numpy.ndarray, List, torch.Tensor, warp.types.array]] = None) None
Set body masses for prims in the view.
- Parameters
masses (Union[np.ndarray, torch.Tensor, wp.array]) – body masses for prims in kg. 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 rigid body masses for all the rigid bodies to the indicated values. >>> prims.set_masses(np.full(num_envs, 10.0)) >>> >>> # set the rigid body masses for the first, middle and last of the 5 envs >>> prims.set_masses(np.full(3, 10.0), indices=np.array([0, 2, 4]))
- set_sleep_thresholds(thresholds: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None) None
Set sleep thresholds of prims in the view.
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- Parameters
thresholds (Optional[Union[np.ndarray, torch.Tensor, wp.array]]) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2. 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 all rigid body densities to the specified values >>> prims.set_sleep_thresholds(np.full(num_envs, 1e-5)) >>> >>> # set rigid body densities for the first, middle and last of the 5 envs >>> prims.set_sleep_thresholds(np.full(3, 1e-5), indices=np.array([0, 2, 4]))
- set_velocities(velocities: Union[numpy.ndarray, torch.Tensor, warp.types.array], 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 rigid prim 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 rigid prim kinematic state:
set_velocities
(set_linear_velocities
,set_angular_velocities
)Example:
>>> # set each rigid prim linear velocity to (1., 1., 1.) and angular velocity to (5., 5., 5.) >>> velocities = np.ones((num_envs, 6)) >>> velocities[:,3:] = 5.0 >>> prims.set_velocities(velocities) >>> >>> # set only the rigid prim velocities for the first, middle and last of the 5 envs >>> velocities = np.ones((3, 6)) >>> velocities[:,3:] = 5.0 >>> 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 specified 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 rigid prims 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 rigid prims 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]))
Rigid Contact View
- class RigidContactView(prim_paths_expr: Union[str, List[str]], filter_paths_expr: Union[List[str], List[List[str]]], name: str = 'rigid_contact_view', prepare_contact_sensors: bool = True, disable_stablization: bool = True, max_contact_count: int = 0)
Provides high level functions to deal with rigid prims (one or many) that track their contacts through filters as well as their attributes/properties.
This class wraps all matching rigid prims found at the regex provided at the
prim_paths_expr
argumentWarning
The rigid prim 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]/Cube” will match /World/Env1/Cube, /World/Env2/Cube..etc. (a non regex prim path can also be used to encapsulate one rigid prim). Additionally a list of regex can be provided. example [“/World/Env[1-5]/Cube”, “/World/Env[10-19]/Cube”].
Union[List[str] (filter_paths_expr) – list of prim paths regex to filter the contacts for each corresponding prim_paths_expr. Example: [“/World/envs/env_2/Xform”] will filter the contacts corresponding to the expression passed.
List[List[str]]] – list of prim paths regex to filter the contacts for each corresponding prim_paths_expr. Example: [“/World/envs/env_2/Xform”] will filter the contacts corresponding to the expression passed.
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 “rigid_contact_view”.
prepare_contact_sensors (bool, Optional) – if rigid prims in the view are not cloned from a prim in a prepared state, (although slow for large number of prims) this ensures that appropriate physics settings are applied on all the prim in the view.
disable_stablization (bool, optional) – disables the contact stabilization parameter in the physics context
max_contact_count (int, optional) – maximum number of contact data to report when detailed contact information is needed
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.cloner import GridCloner >>> from omni.isaac.core.prims import RigidContactView >>> from pxr import UsdGeom >>> >>> env_zero_path = "/World/envs/env_0" >>> num_envs = 5 >>> >>> # clone the environment (num_envs) >>> cloner = GridCloner(spacing=0) >>> cloner.define_base_env(env_zero_path) >>> UsdGeom.Xform.Define(stage_utils.get_current_stage(), env_zero_path) >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform", "Xform") >>> stage_utils.get_current_stage().DefinePrim(f"{env_zero_path}/Xform/Cube", "Cube") >>> # position the cubes on top of each other >>> position_offsets = np.zeros((num_envs, 3)) >>> position_offsets[:, 2] = np.arange(num_envs) * 1.1 >>> env_pos = cloner.clone( ... source_prim_path=env_zero_path, ... prim_paths=cloner.generate_paths("/World/envs/env", num_envs), ... position_offsets=position_offsets ... copy_from_source=True, ... ) >>> >>> # wrap the prims >>> prims = RigidContactView( ... prim_paths_expr="/World/envs/env.*/Xform", ... name="RigidContactView_view", ... filter_paths_expr=["/World/envs/env_2/Xform"], ... max_contact_count=10, ... ) >>> prims <omni.isaac.core.prims.rigid_contact_view.RigidContactView object at 0x7f8d4eb1abf0>
- get_contact_force_data(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Get more detailed contact information between the prims in the view and the filter prims.
Specifically, this method provides individual contact normals, contact points, contact separations as well as contact forces for each pair (the sum of which equals the forces that the
get_contact_force_matrix
method provides as the force aggregate of a pair)Given to the dynamic nature of collision between bodies, this method will provide buffers of contact data which are arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of
(num_shapes, num_filters)
wherenum_filters
is determined according to thefilter_paths_expr
parameter- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for normal forces with shape (max_contact_count, 1), points with shape (max_contact_count, 3), normals with shape (max_contact_count, 3), and distances with shape (max_contact_count, 1), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
Example:
>>> # get detailed contact force data between the prims and the filter prims (the cube in the middle) >>> data = prims.get_contact_force_data() >>> data[0] # normal forces [[-168.53815] [ -89.57392] [-156.10307] [ -75.17234] [ 98.0681 ] [ 52.56319] [ 108.26558] [ 67.62025] [ 0. ] [ 0. ]] >>> data[1] # points [[ 0.4948182 -0.49902824 1.5001888 ] [ 0.4950411 0.49933064 1.5001996 ] [-0.5024581 0.49930018 1.5001924 ] [-0.5024276 -0.49880558 1.5001817 ] [-0.5023767 0.497138 2.5001519 ] [-0.502735 -0.49877006 2.5001822 ] [ 0.4947694 -0.4989927 2.500226 ] [ 0.4949917 0.49677914 2.5001955 ] [ 0. 0. 0. ] [ 0. 0. 0. ]] >>> data[2] # normals [[-4.3812128e-05 3.0501858e-05 1.0000000e+00] [-4.3812128e-05 3.0501858e-05 1.0000000e+00] [-4.3812128e-05 3.0501858e-05 1.0000000e+00] [-4.3812128e-05 3.0501858e-05 1.0000000e+00] [ 2.1408198e-06 -7.0731985e-05 1.0000000e+00] [ 2.1408198e-06 -7.0731985e-05 1.0000000e+00] [ 2.1408198e-06 -7.0731985e-05 1.0000000e+00] [ 2.1408198e-06 -7.0731985e-05 1.0000000e+00] [ 0.0000000e+00 0.0000000e+00 0.0000000e+00] [ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] >>> data[3] # distances [[ 3.7143487e-05] [-4.0254322e-06] [-4.0531158e-05] [ 6.0737699e-07] [ 1.9307560e-04] [ 9.2272363e-05] [ 4.6372414e-05] [ 1.4718286e-04] [ 0.0000000e+00] [ 0.0000000e+00]] >>> data[4] # pair contacts count [[0] [4] [0] [4] [0]] >>> data[5] # start indices of pair contacts [[0] [0] [4] [4] [8]]
- get_contact_force_matrix(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get the contact forces between the prims in the view and the filter prims.
E.g., a matrix of dimension
(num_shapes, num_filters, 3)
wherenum_filters
is determined according to thefilter_paths_expr
parameter- 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. The function returns contact impulses if the default dt is used
- Returns
Net contact forces between the view prim and the filter prims with shape (M, self.num_filters, 3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the contact forces between the prims and the filter prims (the cube in the middle) >>> prims.get_contact_force_matrix() [[[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] [[ 2.2649009e-02 -1.3710857e-02 -4.9047806e+02]] [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]] [[-3.3276828e-03 -2.3870371e-02 3.2733777e+02]] [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00]]]
- get_friction_data(indices: Optional[Union[numpy.ndarray, list, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Tuple[Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray], Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]]
Gets friction data between the prims in the view and the filter prims. Specifically, this method provides frictional contact forces, and points. The data in reported for number of anchor points that includes tangential forces in a single tangent direction to contact normal. Given to the dynamic nature of collision between bodies, this method will provide buffers of friction data arranged sequentially for each pair. The starting index and the number of contact data points for each pair in this stream can be realized from pair_contacts_start_indices, and pair_contacts_count tensors. They both have a dimension of (self.num_shapes, self.num_filters) where filter_count is determined according to the filter_paths_expr parameter.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor, wp.array]], optional) – indicies 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. If the default value is used then the forces are in fact contact impulses
- Returns
- Tuple[Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray],
Union[np.ndarray, torch.Tensor, wp.indexedarray], Union[np.ndarray, torch.Tensor, wp.indexedarray]]: A set of buffers for tangential forces per patch (at number of anchor points, each in a single directions) with shape (max_contact_count, 3), points with shape (max_contact_count, 3), as well as two tensors with shape (M, self.num_filters) to indicate the starting index and the number of contact data points per pair in the aforementioned buffers.
- get_net_contact_forces(indices: Optional[Union[numpy.ndarray, torch.Tensor, warp.types.array]] = None, clone: bool = True, dt: float = 1.0) Union[numpy.ndarray, torch.Tensor, warp.types.indexedarray]
Get the overall net contact forces on 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.
dt (float) – time step multiplier to convert the underlying impulses to forces. The function returns contact impulses if the default dt is used
- Returns
Net contact forces of the prims with shape (M,3).
- Return type
Union[np.ndarray, torch.Tensor, wp.indexedarray]
Example:
>>> # get the net contact force on all rigid bodies. Returned shape is (5, 3). >>> prims.get_net_contact_forces() [[ 1.8731881e-03 5.4876995e-03 1.6408131e+02] [ 1.9060407e-02 -2.2513291e-02 1.6358723e+02] [-2.1011427e-02 3.5647806e-02 1.6371542e+02] [ 9.4006478e-05 -9.3258200e-03 1.6348369e+02] [ 9.3709816e-05 -9.2963902e-03 1.6296776e+02]] >>> >>> # get the net contact force on the rigid bodies for the first, middle and last of the 5 envs >>> prims.get_net_contact_forces(indices=np.array([0, 2, 4])) [[ 1.8731881e-03 5.4876995e-03 1.6408131e+02] [-2.1011427e-02 3.5647806e-02 1.6371542e+02] [ 9.3709816e-05 -9.2963902e-03 1.6296776e+02]]
- 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 rigid prim 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()
- is_physics_handle_valid() bool
Check if rigid prim 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
True if the physics handle of the view is valid (i.e physics is initialized for the view). Otherwise False.
- Return type
bool
Example:
>>> prims.is_physics_handle_valid() True
- property num_filters: int
- Returns
number of filters bodies that report their contact with the rigid prims.
- Return type
int
Example:
>>> prims.num_filters 1
- property num_shapes: int
- Returns
number of rigid shapes for the prims in the view.
- Return type
int
Example:
>>> prims.num_shapes 5
Cloth Prim
- class ClothPrim(prim_path: str, particle_system: omni.isaac.core.prims.soft.particle_system.ParticleSystem, particle_material: Optional[omni.isaac.core.materials.particle_material.ParticleMaterial] = None, name: Optional[str] = 'cloth', position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, particle_mass: Optional[float] = 0.01, pressure: Optional[float] = None, particle_group: Optional[int] = 0, self_collision: Optional[bool] = True, self_collision_filter: Optional[bool] = True, stretch_stiffness: Optional[float] = None, bend_stiffness: Optional[float] = None, shear_stiffness: Optional[float] = None, spring_damping: Optional[float] = None)
Cloth primitive object provide functionalities to create and control cloth parameters
- 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)
- 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_cloth_bend_stiffness() float
Reports a single value that would be used to generate the stiffnesses. This API does not report the actually created stiffnesses.
- Returns
The bend stiffness.
- Return type
float
- get_cloth_damping() Union[numpy.ndarray, torch.Tensor]
Reports a single value that would be used to generate the dampings. This API does not report the actually created dampings.
- Returns
The spring damping.
- Return type
float
- get_cloth_shear_stiffness() float
Reports a single value that would be used to generate the stiffnesses. This API does not report the actually created stiffnesses.
- Returns
The shear stiffness.
- Return type
float
- get_cloth_stretch_stiffness() float
Reports a single value that would be used to generate the stiffnesses. This API does not report the actually created stiffnesses.
- Returns
The stretch stiffness.
- Return type
float
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Return the DynamicState that contains the position and orientation of the cloth prim
- Returns
- position (np.ndarray, optional):
position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.
- orientation (np.ndarray, 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.
- Return type
- 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
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_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_particle_group() int
- Returns
self collision.
- Return type
bool
- get_pressure() float
- Returns
pressure value.
- Return type
float
- get_self_collision() bool
- Returns
self collision.
- Return type
bool
- get_self_collision_filter() bool
- Returns
self collision filter.
- Return type
bool
- get_spring_damping() Union[numpy.ndarray, torch.Tensor]
Gets damping values of spring constraints
- Returns
The spring damping.
- Return type
Union[np.ndarray, torch.Tensor]
- get_stretch_stiffness() Union[numpy.ndarray, torch.Tensor]
Gets stretch stiffness values of spring constraints
- Returns
The stretch stiffness.
- Return type
float
- 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.]
- 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:
>>> 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 mesh: pxr.UsdGeom.Mesh
Returns: Usd.Prim: USD Prim object that this object tracks.
- property name: Optional[str]
Returns: str: name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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
- 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 theset_joints_default_state
method) are imposedExample:
>>> 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_cloth_bend_stiffness(stiffness: float) None
Sets a single bend stiffness value to all springs constraints in the cloth
- Parameters
stiffness (float) – The cloth springs bend stiffness value. Range: [0 , inf), Units: force/distance = mass/second/second
- set_cloth_damping(damping: float) None
Sets a single damping value to all springs constraints in the cloth
- Parameters
damping (float) – The cloth springs damping value. Range: [0 , inf), Units: force/velocity = mass/second
- set_cloth_shear_stiffness(stiffness: float) None
Sets a single shear stiffness value to all springs constraints in the cloth
- Parameters
stiffness (float) – The cloth springs shear stiffness value. Range: [0 , inf), Units: force/distance = mass/second/second
- set_cloth_stretch_stiffness(stiffness: Union[numpy.ndarray, torch.Tensor]) None
Sets a single stretch stiffness value to all springs constraints in the cloth
- Parameters
stiffness (Union[np.ndarray, torch.Tensor]) – The cloth springs stretch stiffness value. Range: [0 , inf), Units: force/distance = mass/second/second
- 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_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_particle_group(particle_group: int) None
- Parameters
particle_group (int) – particle group.
- set_pressure(pressure: float) None
- Parameters
pressure (float) – pressure value.
- set_self_collision(self_collision: bool) None
- Parameters
self_collision (bool) – self collision.
- set_self_collision_filter(self_collision_filter: bool) None
- Parameters
self_collision_filter (bool) – self collision filter.
- set_spring_damping(damping: Union[numpy.ndarray, torch.Tensor]) None
Sets damping values of spring constraints in the cloth
- Parameters
damping (List[float]) – The damping values of springs. Range: [0 , inf), Units: force/distance = mass/second
- set_stretch_stiffness(stiffness: Union[numpy.ndarray, torch.Tensor]) None
Sets stretch stiffness values of spring constraints in the cloth It represents a stiffness for linear springs placed between particles to counteract stretching.
- Parameters
stiffness (Union[np.ndarray, torch.Tensor]) – The stretch stiffnesses. Range: [0 , inf), Units: force/distance = mass/second/second
- 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.]))
Cloth Prim View
- class ClothPrimView(prim_paths_expr: str, particle_systems: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_materials: Optional[Union[numpy.ndarray, torch.Tensor]] = None, name: str = 'cloth_prim_view', reset_xform_properties: bool = True, positions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, translations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, visibilities: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_masses: Optional[Union[numpy.ndarray, torch.Tensor]] = None, pressures: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_groups: Optional[Union[numpy.ndarray, torch.Tensor]] = None, self_collisions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, self_collision_filters: Optional[Union[numpy.ndarray, torch.Tensor]] = None, stretch_stiffnesses: Optional[Union[numpy.ndarray, torch.Tensor]] = None, bend_stiffnesses: Optional[Union[numpy.ndarray, torch.Tensor]] = None, shear_stiffnesses: Optional[Union[numpy.ndarray, torch.Tensor]] = None, spring_dampings: Optional[Union[numpy.ndarray, torch.Tensor]] = None)
The view class for cloth prims.
- 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 count: int
Returns: int: cloth counts.
- 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_cloths_bend_stiffnesses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the value of bend stiffness set to all the springs within cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
bend stiffness tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_cloths_dampings(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the value of damping set for all the springs within cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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 tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_cloths_shear_stiffnesses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the value of shear stiffness set to all the springs within cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
shear stiffness tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_cloths_stretch_stiffnesses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the value of stretch stiffness set to all the springs within cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
stretch stiffness tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- 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
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_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 translations 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 prims 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 [[ 1.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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 [[ 1.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> 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_particle_groups(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the particle groups of the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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 groups with shape (M, ).
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_particle_masses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the particle masses for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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 tensor with shape (M, max_particles_per_cloth)
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_pressures(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the pressures of the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
cloths pressure with shape (M, ).
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_self_collision_filters(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the self collision filters for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
the self collision filters tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_self_collisions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the self collision for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
the self collision tensor with shape (M, )
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_spring_dampings(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the spring damping for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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 tensor with shape (M, max_springs_per_cloth)
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_stretch_stiffnesses(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the spring stretch stiffness for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
stiffness tensor with shape (M, max_springs_per_cloth)
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- get_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the particle velocities for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
velocity tensor with shape (M, max_particles_per_cloth, 3)
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- 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, 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).
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 prims 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.5 -0.75 0. ] [ 1.5 0.75 0. ] [ 0. -0.75 0. ] [ 0. 0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]] >>> >>> # get only the prims 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.5 -0.75 0. ] [ 0. -0.75 0. ] [-1.5 -0.75 0. ]] >>> orientations [[1. 0. 0. 0.] [1. 0. 0. 0.] [1. 0. 0. 0.]]
- get_world_positions(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
Gets the particle world positions for the cloths indicated by the indices.
- Parameters
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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
position tensor with shape (M, max_particles_per_cloth, 3)
- Return type
Union[Tuple[np.ndarray, np.ndarray], Tuple[torch.Tensor, torch.Tensor]]
- 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 creates a rigid body view in physX.
- Parameters
physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.
- property is_non_root_articulation_link: bool
Returns: bool: True if the prim corresponds to a non root link in an articulation. Otherwise False.
- 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, 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 max_particles_per_cloth: int
Returns: int: maximum number of particles per cloth.
- property max_springs_per_cloth: int
Returns: int: maximum number of springs per cloth.
- property name: str
Returns: str: name given to the prims view when instantiating it.
- post_reset() None
Reset the prims to its default state (positions and orientations)
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>)]
- set_cloths_bend_stiffnesses(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets a single value of bend stiffnesses to all the springs within cloths indicated by the indices.
- Parameters
values (Union[np.ndarray, torch.Tensor]) – cloth spring bend stiffness values with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_cloths_dampings(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets a single value of damping to all the springs within cloths indicated by the indices.
- Parameters
values (Union[np.ndarray, torch.Tensor]) – cloth spring damping with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_cloths_shear_stiffnesses(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets a single value of shear stiffnesses to all the springs within cloths indicated by the indices.
- Parameters
values (Union[np.ndarray, torch.Tensor]) – cloth spring shear stiffness values with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_cloths_stretch_stiffnesses(values: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets a single value of stretch stiffnesses to all the springs within cloths indicated by the indices.
- Parameters
values (Union[np.ndarray, torch.Tensor]) – cloth spring stretch stiffness values with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_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()
orworld.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_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 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_local_poses(positions, orientations) >>> >>> # reposition only the prims 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_particle_groups(particle_groups: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the particle group of the cloths indicated by the indices.
- Parameters
particle_groups (Union[np.ndarray, torch.Tensor]) – particle group with shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_masses(masses: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the particle masses for the cloths indicated by the indices.
- Parameters
masses (Union[np.ndarray, torch.Tensor]) – cloth particle masses with the shape (M, max_particles_per_cloth, 3).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_pressures(pressures: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the pressures of the cloths indicated by the indices.
- Parameters
pressures (Union[np.ndarray, torch.Tensor]) – cloths pressure with shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_self_collision_filters(self_collision_filters: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the self collision filters for the cloths indicated by the indices.
- Parameters
self_collision_filters (Union[np.ndarray, torch.Tensor]) – self collision filters with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_self_collisions(self_collisions: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the self collision flags for the cloths indicated by the indices.
- Parameters
self_collisions (Union[np.ndarray, torch.Tensor]) – self collision flag with the shape (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_spring_dampings(damping: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the spring damping for the cloths indicated by the indices.
- Parameters
damping (Union[np.ndarray, torch.Tensor]) – cloth spring damping with the shape (M, max_springs_per_cloth).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_stretch_stiffnesses(stiffness: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the spring stretch stiffness values for springs within the cloths indicated by the indices.
- Parameters
stiffness (Union[np.ndarray, torch.Tensor]) – cloth spring stiffness with the shape (M, max_springs_per_cloth).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_velocities(velocities: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the particle velocities for the cloths indicated by the indices.
- Parameters
velocities (Union[np.ndarray, torch.Tensor]) – particle velocities with the shape (M, max_particles_per_cloth, 3).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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_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 prim poses 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 prims. 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 query. 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 prims 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 prims 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]))
- set_world_positions(positions: Optional[Union[numpy.ndarray, torch.Tensor]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Sets the particle world positions for the cloths indicated by the indices.
- Parameters
positions (Union[np.ndarray, torch.Tensor]) – particle positions with the shape (M, max_particles_per_cloth, 3).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], optional) – indices to specify which cloth 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).
Particle System
- class ParticleSystem(prim_path: str, name: Optional[str] = 'particle_system', particle_system_enabled: Optional[bool] = None, simulation_owner: Optional[str] = None, contact_offset: Optional[float] = None, rest_offset: Optional[float] = None, particle_contact_offset: Optional[float] = None, solid_rest_offset: Optional[float] = None, fluid_rest_offset: Optional[float] = None, enable_ccd: Optional[bool] = None, solver_position_iteration_count: Optional[float] = None, max_depenetration_velocity: Optional[float] = None, wind: Optional[Sequence[float]] = None, max_neighborhood: Optional[int] = None, max_velocity: Optional[float] = None, global_self_collision_enabled: Optional[bool] = None, non_particle_collision_enabled: Optional[bool] = None)
A wrapper around PhysX particle system.
PhysX uses GPU-accelerated position-based-dynamics (PBD) particle simulation [1]. The particle system can be used to simulate fluids, cloth and inflatables [2].
The wrapper is useful for creating and setting solver parameters common to the particle objects associated with the system. The particle system’s solver parameters cannot be changed once the scene is playing.
Note
CPU simulation of particles is not supported. PhysX must be simulated with GPU enabled.
- Reference:
[1] https://mmacklin.com/pbf_sig_preprint.pdf [2] https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_physics.html#particle-simulation
- apply_particle_anisotropy() pxr.PhysxSchema.PhysxParticleAnisotropyAPI
Applies anisotropy to the particle system.
This is used to compute anisotropic scaling of particles in a post-processing step. It only affects the rendering output including iso-surface generation.
- apply_particle_isotropy() pxr.PhysxSchema.PhysxParticleAnisotropyAPI
Applies iso-surface extraction to the particle system.
This is used to define settings to extract an iso-surface from the particles in a post-processing step. It only affects the rendering output including iso-surface generation.
- apply_particle_material(particle_materials: omni.isaac.core.materials.particle_material.ParticleMaterial) None
- apply_particle_smoothing() pxr.PhysxSchema.PhysxParticleSmoothingAPI
Applies smoothing to the simulated particle system.
This is used to control smoothing of particles in a post-processing step. It only affects the rendering output including iso-surface generation.
- get_applied_particle_material() omni.isaac.core.materials.particle_material.ParticleMaterial
- get_contact_offset() float
- Returns
The contact offset used for collisions with non-particle objects.
- Return type
float
- get_enable_ccd() bool
- Returns
Whether continuous collision detection for particles is enabled or disabled.
- Return type
bool
- get_fluid_rest_offset() float
- Returns
The rest offset used for fluid-fluid particle interactions.
- Return type
float
- get_global_self_collision_enabled() bool
- Returns
- Whether self collisions to follow particle-object-specific settings
is enabled or disabled.
- Return type
bool
- get_max_depenetration_velocity() None
- Returns
The maximum velocity permitted between intersecting particles.
- Return type
float
- get_max_neighborhood() int
- Returns
The particle neighborhood size.
- Return type
int
- get_max_velocity() float
- Returns
The maximum particle velocity.
- Return type
float
- get_particle_contact_offset() float
- Returns
The contact offset used for interactions between particles.
- Return type
float
- get_particle_system_enabled() bool
- Returns
Whether particle system is enabled or not.
- Return type
bool
- get_rest_offset() float
- Returns
The rest offset used for collisions with non-particle objects.
- Return type
float
- get_simulation_owner() pxr.Usd.Prim
- Returns
The physics scene prim attached to particle system.
- Return type
Usd.Prim
- get_solid_rest_offset() float
- Returns
The rest offset used for solid-solid or solid-fluid particle interactions.
- Return type
float
- get_solver_position_iteration_count() int
- Returns
The number of solver iterations for positions.
- Return type
int
- get_wind() Sequence[float]
- Returns
The wind applied to the current particle system.
- Return type
Sequence[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 name: Optional[str]
Returns: str: name given to the prim when instantiating it. Otherwise None.
- property particle_system: pxr.PhysxSchema.PhysxParticleSystem
Returns: PhysxSchema.PhysxParticleSystem: The particle system.
- post_reset() None
- property prim: pxr.Usd.Prim
Returns: Usd.Prim: The USD prim present.
- property prim_path: str
Returns: str: The stage path to the particle system.
- set_contact_offset(value: float) None
Set the contact offset used for collisions with non-particle objects such as rigid or deformable bodies.
- Parameters
value (float) – The contact offset.
- set_enable_ccd(value: bool) None
Enable continuous collision detection for particles.
- Parameters
value (bool) – Whether to enable or disable.
- set_fluid_rest_offset(value: float) None
Set the rest offset used for fluid-fluid particle interactions.
Note: Must be smaller than particle contact offset.
- Parameters
value (float) – The rest offset.
- set_global_self_collision_enabled(value: bool) None
Enable self collisions to follow particle-object-specific settings.
If True, self collisions follow particle-object-specific settings. If False, all particle self collisions are disabled, regardless of any other settings.
Note: Improves performance if self collisions are not needed.
- Parameters
value (bool) – Whether to enable or disable.
- set_max_depenetration_velocity(value: float) None
Set the maximum velocity permitted to be introduced by the solver to depenetrate intersecting particles.
- Parameters
value (float) – The maximum depenetration velocity.
- set_max_neighborhood(value: int) None
Set the particle neighborhood size.
- Parameters
value (int) – The neighborhood size.
- set_max_velocity(value: float) None
Set the maximum particle velocity.
- Parameters
value (float) – The maximum velocity.
- set_particle_contact_offset(value: float) None
Set the contact offset used for interactions between particles.
Note: Must be larger than solid and fluid rest offsets.
- Parameters
value (float) – The contact offset.
- set_particle_system_enabled(value: bool) None
Set enabling of the particle system.
- Parameters
value (bool) – Whether to enable or disable.
- set_rest_offset(value: float) None
Set the rest offset used for collisions with non-particle objects such as rigid or deformable bodies.
- Parameters
value (float) – The rest offset.
- set_simulation_owner(value: str) None
Set the PhysicsScene that simulates this particle system.
- Parameters
value (str) – The prim path to the physics scene.
- set_solid_rest_offset(value: float) None
Set the rest offset used for solid-solid or solid-fluid particle interactions.
Note: Must be smaller than particle contact offset.
- Parameters
value (float) – The rest offset.
- set_solver_position_iteration_count(value: int) None
Set the number of solver iterations for position.
- Parameters
value (int) – Number of solver iterations.
- set_wind(value: Sequence[float]) None
Set the wind velocity applied to the current particle system.
- Parameters
value (Sequence[float]) – The wind applied to the current particle system.
Particle System View
- class ParticleSystemView(prim_paths_expr: str, name: str = 'particle_system_view', particle_systems_enabled: Optional[Union[numpy.ndarray, torch.Tensor]] = None, simulation_owners: Optional[Sequence[str]] = None, contact_offsets: Optional[Union[numpy.ndarray, torch.Tensor]] = None, rest_offsets: Optional[Union[numpy.ndarray, torch.Tensor]] = None, particle_contact_offsets: Optional[Union[numpy.ndarray, torch.Tensor]] = None, solid_rest_offsets: Optional[Union[numpy.ndarray, torch.Tensor]] = None, fluid_rest_offsets: Optional[Union[numpy.ndarray, torch.Tensor]] = None, enable_ccds: Optional[Union[numpy.ndarray, torch.Tensor]] = None, solver_position_iteration_counts: Optional[Union[numpy.ndarray, torch.Tensor]] = None, max_depenetration_velocities: Optional[Union[numpy.ndarray, torch.Tensor]] = None, winds: Optional[Union[numpy.ndarray, torch.Tensor]] = None, max_neighborhoods: Optional[int] = None, max_velocities: Optional[Union[numpy.ndarray, torch.Tensor]] = None, global_self_collisions_enabled: Optional[Union[numpy.ndarray, torch.Tensor]] = None)
Provides high level functions to deal with particle systems (1 or more particle systems) as well as its attributes/ properties. This object wraps all matching particle systems found at the regex provided at the prim_paths_expr. Note: not all the attributes of the PhysxSchema.PhysxParticleSystem is currently controlled with this view class Tensor API support will be added in the future to extend the functionality of this class to applications beyond cloth.
- apply_particle_materials(particle_materials: Union[omni.isaac.core.materials.particle_material.ParticleMaterial, List[omni.isaac.core.materials.particle_material.ParticleMaterial]], indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) None
Used to apply particle material to prims in the view.
- Parameters
particle_materials (Union[ParticleMaterial, List[ParticleMaterial]]) – particle materials to be applied to prims in the view. Note: if a physics material is not defined, the defaults will be used from PhysX. 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.
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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 physics materials != length of prims indexed
- property count: int
Returns: int: number of rigid shapes for the prims in the view.
- get_applied_particle_materials(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) List[omni.isaac.core.materials.particle_material.ParticleMaterial]
Gets the applied particle material to prims in the view.
- 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
the current applied particle materials for prims in the view.
- Return type
List[ParticleMaterial]
- get_contact_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
The contact offset used for collisions with non-particle objects for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_enable_ccds(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
Whether continuous collision detection for particles is enabled or disabled for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_fluid_rest_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
- Returns
The rest offset used for fluid-fluid particle interactions. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.
- get_global_self_collisions_enabled(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
- Whether self collisions to follow particle-object-specific settings
is enabled or disabled. for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_max_depenetration_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
- The maximum velocity permitted to be introduced by the solver to
depenetrate intersecting particles for particle systems for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_max_neighborhoods(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
The particle neighborhood size for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_max_velocities(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
The maximum particle velocities for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_particle_contact_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
- Returns
The contact offset used for interactions between particles in the view concatenated. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.
- get_particle_systems_enabled(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
Whether particle system is enabled or not for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_rest_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
The rest offset used for collisions with non-particle objects for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_simulation_owners(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Sequence[str]
- Returns
The physics scene prim path attached to particle system. shape is (M, ).
- Return type
Sequence[str]
- 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)
- get_solid_rest_offsets(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
- Returns
The rest offset used for solid-solid or solid-fluid particle interactions. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.
- get_solver_position_iteration_counts(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None) Union[numpy.ndarray, torch.Tensor]
- Returns
The number of solver iterations for positions for each particle system. shape is (M, ).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
- get_winds(indices: Optional[Union[numpy.ndarray, list, torch.Tensor]] = None, clone: bool = True) Union[numpy.ndarray, torch.Tensor]
- Returns
The winds applied to the current particle system. shape is (M, 3).
- Return type
Union[np.ndarray, torch.Tensor]
- 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)
clone (bool, optional) – True to return a clone of the internal buffer. Otherwise False. Defaults to True.
- initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None
Create a physics simulation view if not passed and creates a Particle System View.
- 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_contact_offsets(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the contact offset used for collisions with non-particle objects such as rigid or deformable bodies for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_enable_ccds(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Enable continuous collision detection for particles for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_fluid_rest_offsets(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the rest offset used for fluid-fluid particle interactions.
Note: Must be smaller than particle contact offset.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – fluid rest offset to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_global_self_collisions_enabled(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Enable self collisions to follow particle-object-specific settings for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_max_depenetration_velocities(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the maximum velocity permitted to be introduced by the solver to depenetrate intersecting particles for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_max_neighborhoods(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the particle neighborhood size for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_max_velocities(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the maximum particle velocity for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_particle_contact_offsets(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the contact offset used for interactions between particles.
Note: Must be larger than solid and fluid rest offsets.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – The contact offset.
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_particle_systems_enabled(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set enabling of the particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_rest_offsets(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the rest offset used for collisions with non-particle objects such as rigid or deformable bodies for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_simulation_owners(values: Sequence[str], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the PhysicsScene that simulates particle systems.
- Parameters
values (Sequence[str]) – PhysicsScene list to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_solid_rest_offsets(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the rest offset used for solid-solid or solid-fluid particle interactions.
Note: Must be smaller than particle contact offset.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – solid rest offset to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_solver_position_iteration_counts(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the number of solver iterations for position for particle systems.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – maximum particle velocity tensor to set particle systems to. shape is (M, ).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
- set_winds(values: Union[numpy.ndarray, torch.Tensor], indices: Optional[Union[numpy.ndarray, List, torch.Tensor]] = None) None
Set the winds velocities applied to the current particle system.
- Parameters
values (Optional[Union[np.ndarray, torch.Tensor]]) – The wind applied to the current particle system. shape is (M, 3).
indices (Optional[Union[np.ndarray, list, torch.Tensor]], 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).
Robots
Robot
- class Robot(prim_path: str, name: str = 'robot', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: bool = True, articulation_controller: Optional[omni.isaac.core.controllers.articulation_controller.ArticulationController] = None)
Implementation (on
Articulation
class) to deal with an articulation prim as a robotWarning
The robot (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 “robot”.
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.robots import Robot >>> >>> 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 a robot (articulation) >>> prim = Robot(prim_path=prim_path, name="franka_panda") >>> print(prim) <omni.isaac.core.robots.robot.Robot object at 0x7fdd4875a1d0>
- 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
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
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
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 typeArticulationController
(a Proportional-Derivative controller that can apply position targets, velocity targets and efforts) will be used- Returns
articulation controller
- Return type
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
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
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
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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- 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 robot to its default state
Note
For a robot, 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 theset_joints_default_state
method) are imposedExample:
>>> 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()
orworld.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,).
Robot View
- class RobotView(prim_paths_expr: str, name: str = 'rigid_prim_view', positions: Optional[Union[numpy.ndarray, torch.Tensor]] = None, translations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, orientations: Optional[Union[numpy.ndarray, torch.Tensor]] = None, scales: Optional[Union[numpy.ndarray, torch.Tensor]] = None, visibilities: Optional[Union[numpy.ndarray, torch.Tensor]] = None)
Implementation (on
ArticulationView
class) to deal with articulation prims as robotsThis class wraps all matching articulations found at the regex provided at the
prim_paths_expr
argumentWarning
The robot (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 (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 “rigid_prim_view”.
positions (Optional[Union[np.ndarray, torch.Tensor]], 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]], 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]], 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]], 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]], optional) – set to false for an invisible prim in the stage while rendering. shape is (N,). Defaults to None.
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.isaac.cloner import GridCloner >>> from omni.isaac.core.robots import RobotView >>> 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 robots >>> prims = RobotView(prim_paths_expr="/World/envs/env.*/panda", name="franka_panda_view") >>> print(prims) <omni.isaac.core.robots.robot_view.RobotView object at 0x7f12785a5fc0>
- 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
andset_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
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
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
orforce
- 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
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
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_link_index(link_name: str) int
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
- property is_non_root_articulation_link: bool
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 robots to their default states
Note
For the robots, 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 theset_joints_default_state
method) and the joint’s stiffness and dampings (defined via theset_gains
method) are imposedExample:
>>> 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()
orworld.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
orforce
.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 theapply_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 theapply_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()
orworld.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 jointsThis 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 DOFThis 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]))
Scenes
Scene
- class Scene
Provide methods to add objects of interest in the stage to retrieve their information and set their reset default state in an easy way
Example:
>>> from omni.isaac.core.scenes import Scene >>> >>> scene = Scene() >>> scene <omni.isaac.core.scenes.scene.Scene object at 0x...>
- add(obj: omni.isaac.core.prims.xform_prim.XFormPrim) omni.isaac.core.prims.xform_prim.XFormPrim
Add an object to the scene registry
- Parameters
obj (XFormPrim) – object to be added
- Raises
Exception – The object type is not supported yet
- Returns
object
- Return type
Example:
>>> from omni.isaac.core.prims import XFormPrimView >>> >>> prims = XFormPrimView(prim_paths_expr="/World") >>> scene.add(prims) <omni.isaac.core.prims.xform_prim_view.XFormPrimView object at 0x...>
- add_default_ground_plane(z_position: float = 0, name='default_ground_plane', prim_path: str = '/World/defaultGroundPlane', static_friction: float = 0.5, dynamic_friction: float = 0.5, restitution: float = 0.8) omni.isaac.core.objects.ground_plane.GroundPlane
Create a ground plane (using the default asset for Isaac Sim environments) and add it to the scene registry
- Parameters
z_position (float, optional) – ground plane position in the z-axis. Defaults to 0.
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 “default_ground_plane”.
prim_path (str, optional) – prim path of the prim to create. Defaults to “/World/defaultGroundPlane”.
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.
- Returns
ground plane instance
- Return type
Example:
>>> scene.add_default_ground_plane() server... <omni.isaac.core.objects.ground_plane.GroundPlane object at 0x...>
- add_ground_plane(size: Optional[float] = None, z_position: float = 0, name='ground_plane', prim_path: str = '/World/groundPlane', static_friction: float = 0.5, dynamic_friction: float = 0.5, restitution: float = 0.8, color: Optional[numpy.ndarray] = None) omni.isaac.core.objects.ground_plane.GroundPlane
Create a ground plane and add it to the scene registry
- Parameters
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.
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”.
prim_path (str, optional) – prim path of the prim to create. Defaults to “/World/groundPlane”.
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.
color (Optional[np.ndarray], optional) – color of the visual plane. Defaults to None, which means 50% gray
- Returns
ground plane instance
- Return type
Example:
>>> scene.add_ground_plane() <omni.isaac.core.objects.ground_plane.GroundPlane object at 0x...>
- clear(registry_only: bool = False) None
Clear the stage from all added objects to the scene registry.
- Parameters
registry_only (bool, optional) – True to remove the object from the scene registry only and not the USD. Defaults to False.
Example:
>>> scene.clear()
- compute_object_AABB(name: str) Tuple[numpy.ndarray, numpy.ndarray]
Compute the bounding box points (minimum and maximum) of a registered object given its name
Warning
The bounding box computations should be enabled, via the
enable_bounding_boxes_computations
method, before querying the Axis-Aligned Bounding Box (AABB) of an object- Parameters
name (str) – object name
- Raises
Exception – If the bounding box computation is not enabled
- Returns
bounding box points (minimum and maximum)
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> scene.enable_bounding_boxes_computations() >>> >>> bbox = scene.compute_object_AABB("ground_plane") >>> bbox[0] # minimum array([-50., -50., 0.]) >>> bbox[1] # maximum array([50., 50., 0.])
- disable_bounding_boxes_computations() None
Disable the bounding boxes computations
Example:
>>> scene.disable_bounding_boxes_computations()
- enable_bounding_boxes_computations() None
Enable the bounding boxes computations
Example:
>>> scene.enable_bounding_boxes_computations()
- get_object(name: str) omni.isaac.core.prims.xform_prim.XFormPrim
Get a registered object by its name if exists otherwise None
Note
Object can be registered via the
add
method- Parameters
str (name) – object name
- Returns
object if it exists otherwise None
- Return type
Example:
>>> # given a default ground plane named 'default_ground_plane' >>> scene.get_object("default_ground_plane") <omni.isaac.core.objects.ground_plane.GroundPlane object at 0x...>
- object_exists(name: str) bool
Check if an object exists in the scene registry
- Parameters
name (str) – object name
- Returns
whether the object exists in the scene registry or not
- Return type
bool
Example:
>>> # given a default ground plane named 'default_ground_plane' >>> scene.object_exists("default_ground_plane") True
- post_reset() None
Call the
post_reset
method on all added objects to the scene registryExample:
>>> scene.post_reset()
- remove_object(name: str, registry_only: bool = False) None
Remove and object from the scene registry and the USD stage if specified (enable by default)
- Parameters
name (str) – Name of the prim to be removed.
registry_only (bool, optional) – True to remove the object from the scene registry only and not the USD. Defaults to False.
Example:
>>> # given a default ground plane named 'default_ground_plane' >>> scene.remove_object("default_ground_plane")
- property stage: pxr.Usd.Stage
- Returns
current USD stage
- Return type
Usd.Stage
Example:
>>> scene.stage Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x...usd'), sessionLayer=Sdf.Find('anon:0x...usda'), pathResolverContext=<invalid repr>)
SceneRegistry
- class SceneRegistry
Class to keep track of the different types of objects added to the scene
Example:
>>> from omni.isaac.core.scenes import SceneRegistry >>> >>> scene_registry = SceneRegistry() >>> scene_registry <omni.isaac.core.scenes.scene_registry.SceneRegistry object at 0x...>
- add_articulated_system(name: str, articulated_system: omni.isaac.core.articulations.articulation.Articulation) None
Register a
Articulation
(or subclass) object- Parameters
name (str) – object name
articulated_system (Articulation) – object
- add_articulated_view(name: str, articulated_view: omni.isaac.core.articulations.articulation_view.ArticulationView) None
Register a
ArticulationView
(or subclass) object- Parameters
name (str) – object name
articulated_view (ArticulationView) – object
- add_cloth(name: str, cloth: omni.isaac.core.prims.soft.cloth_prim.ClothPrim) None
Register a
ClothPrim
(or subclass) object- Parameters
name (str) – object name
cloth (ClothPrim) – object
- add_cloth_view(name: str, cloth_prim_view: omni.isaac.core.prims.soft.cloth_prim_view.ClothPrimView) None
Register a
ClothPrimView
(or subclass) object- Parameters
name (str) – object name
cloth_prim_view (ClothPrimView) – object
- add_deformable(name: str, deformable: omni.isaac.core.prims.soft.deformable_prim.DeformablePrim) None
Register a
DeformablePrim
(or subclass) object- Parameters
name (str) – object name
deformable (DeformablePrim) – object
- add_deformable_material(name: str, deformable_material: omni.isaac.core.materials.deformable_material.DeformableMaterial) None
Register a
DeformableMaterial
(or subclass) object- Parameters
name (str) – object name
deformable_material (DeformableMaterial) – object
- add_deformable_material_view(name: str, deformable_material_view: omni.isaac.core.materials.deformable_material_view.DeformableMaterialView) None
Register a
DeformableMaterialView
(or subclass) object- Parameters
name (str) – object name
deformable_material_view (DeformableMaterialView) – object
- add_deformable_view(name: str, deformable_prim_view: omni.isaac.core.prims.soft.deformable_prim_view.DeformablePrimView) None
Register a
DeformablePrimView
(or subclass) object- Parameters
name (str) – object name
deformable_prim_view (DeformablePrimView) – object
- add_geometry_object(name: str, geometry_object: omni.isaac.core.prims.geometry_prim.GeometryPrim) None
Register a
GeometryPrim
(or subclass) object- Parameters
name (str) – object name
geometry_object (GeometryPrim) – object
- add_geometry_prim_view(name: str, geometry_prim_view: omni.isaac.core.prims.geometry_prim_view.GeometryPrimView) None
Register a
GeometryPrimView
(or subclass) object- Parameters
name (str) – object name
geometry_prim_view (GeometryPrim) – object
- add_particle_material(name: str, particle_material: omni.isaac.core.materials.particle_material.ParticleMaterial) None
Register a
ParticleMaterial
(or subclass) object- Parameters
name (str) – object name
particle_material (ParticleMaterial) – object
- add_particle_material_view(name: str, particle_material_view: omni.isaac.core.materials.particle_material_view.ParticleMaterialView) None
Register a
ParticleMaterialView
(or subclass) object- Parameters
name (str) – object name
particle_material_view (ParticleMaterialView) – object
- add_particle_system(name: str, particle_system: omni.isaac.core.prims.soft.particle_system.ParticleSystem) None
Register a
ParticleSystem
(or subclass) object- Parameters
name (str) – object name
particle_system (ParticleSystemView) – object
- add_particle_system_view(name: str, particle_system_view: omni.isaac.core.prims.soft.particle_system_view.ParticleSystemView) None
Register a
ParticleSystemView
(or subclass) object- Parameters
name (str) – object name
particle_system_view (ParticleSystemView) – object
- add_rigid_contact_view(name: str, rigid_contact_view: omni.isaac.core.prims.rigid_contact_view.RigidContactView) None
Register a
RigidContactView
(or subclass) object- Parameters
name (str) – object name
rigid_contact_view (RigidContactView) – object
- add_rigid_object(name: str, rigid_object: omni.isaac.core.prims.rigid_prim.RigidPrim) None
Register a
RigidPrim
(or subclass) object- Parameters
name (str) – object name
rigid_object (RigidPrim) – object
- add_rigid_prim_view(name: str, rigid_prim_view: omni.isaac.core.prims.rigid_prim_view.RigidPrimView) None
Register a
RigidPrimView
(or subclass) object- Parameters
name (str) – object name
rigid_prim_view (RigidPrimView) – object
- add_robot(name: str, robot: omni.isaac.core.robots.robot.Robot) None
Register a
Robot
(or subclass) object- Parameters
name (str) – object name
robot (Robot) – object
- add_robot_view(name: str, robot_view: omni.isaac.core.robots.robot_view.RobotView) None
Register a
RobotView
(or subclass) object- Parameters
name (str) – object name
robot_view (RobotView) – object
- add_sensor(name: str, sensor: omni.isaac.core.prims.base_sensor.BaseSensor) None
Register a
BaseSensor
(or subclass) object- Parameters
name (str) – object name
sensor (BaseSensor) – object
- add_xform(name: str, xform: omni.isaac.core.prims.xform_prim.XFormPrim) None
Register a
XFormPrim
(or subclass) object- Parameters
name (str) – object name
robot (Robot) – object
- add_xform_view(name: str, xform_prim_view: omni.isaac.core.prims.xform_prim_view.XFormPrimView) None
Register a
XFormPrimView
(or subclass) object- Parameters
name (str) – object name
xform_prim_view (XFormPrimView) – object
- property articulated_systems: dict
Registered
Articulation
objects
- property articulated_views: dict
Registered
ArticulationView
objects
- property cloth_prim_views: dict
Registered
ClothPrimView
objects
- property cloth_prims: dict
Registered
ClothPrim
objects
- property deformable_material_views: dict
Registered
DeformableMaterialView
objects
- property deformable_materials: dict
Registered
DeformableMaterial
objects
- property deformable_prim_views: dict
Registered
DeformablePrimView
objects
- property deformable_prims: dict
Registered
DeformablePrim
objects
- property geometry_prim_views: dict
Registered
GeometryPrimView
objects
- get_object(name: str) omni.isaac.core.prims.xform_prim.XFormPrim
Get a registered object by its name if exists otherwise None
- Parameters
name (str) – object name
- Returns
the object if it exists otherwise None
- Return type
Example:
>>> # given a registered ground plane named 'default_ground_plane' >>> scene_registry.get_object("default_ground_plane") <omni.isaac.core.objects.ground_plane.GroundPlane object at 0x...>
- name_exists(name: str) bool
Check if an object exists in the registry by its name
- Parameters
name (str) – object name
- Returns
whether the object is registered or not
- Return type
bool
Example:
>>> # given a registered ground plane named 'default_ground_plane' >>> scene_registry.name_exists("default_ground_plane") True
- property particle_material_views: dict
Registered
particle_material_view
objects
- property particle_materials: dict
Registered
ParticleMaterial
objects
- property particle_system_views: dict
Registered
ParticleSystemView
objects
- property particle_systems: dict
Registered
ParticleSystem
objects
- remove_object(name: str) None
Remove and object from the registry
Note
This method will only remove the object from the internal registry. The wrapped object will not be removed from the USD stage
- Parameters
name (str) – object name
- Raises
Exception – If the name doesn’t exist in the registry
Example:
>>> # given a registered ground plane named 'default_ground_plane' >>> scene_registry.remove_object("default_ground_plane")
- property rigid_contact_views: dict
Registered
RigidContactView
objects
- property rigid_objects: dict
Registered
RigidPrim
objects
- property rigid_prim_views: dict
Registered
RigidPrimView
objects
- property robot_views: dict
Registered
RobotView
objects
- property robots: dict
Registered
Robot
objects
- property sensors: dict
Registered
BaseSensor
(and derived) objects
- property xform_prim_views: dict
Registered
XFormPrimView
objects
- property xforms: dict
Registered
XFormPrim
objects
Simulation Context
- class SimulationContext(*args, **kwargs)
This class provide functions that take care of many time-related events such as perform a physics or a render step for instance. Adding/ removing callback functions that gets triggered with certain events such as a physics step, timeline event (pause or play..etc), stage open/ close..etc.
It also includes an instance of PhysicsContext which takes care of many physics related settings such as setting physics dt, solver type..etc.
- Parameters
physics_dt (Optional[float], optional) – dt between physics steps. Defaults to None.
rendering_dt (Optional[float], optional) – dt between rendering steps. Note: rendering means rendering a frame of the current application and not only rendering a frame to the viewports/cameras. So UI elements of Isaac Sim will be refreshed with this dt as well if running non-headless. Defaults to None.
stage_units_in_meters (Optional[float], optional) – The metric units of assets. This will affect gravity value..etc. Defaults to None.
physics_prim_path (Optional[str], optional) – specifies the prim path to create a PhysicsScene at, only in the case where no PhysicsScene already defined. Defaults to “/physicsScene”.
set_defaults (bool, optional) – set to True to use the defaults settings [physics_dt = 1.0/ 60.0, stage units in meters = 0.01 (i.e in cms), rendering_dt = 1.0 / 60.0, gravity = -9.81 m / s ccd_enabled, stabilization_enabled, gpu dynamics turned off, broadcast type is MBP, solver type is TGS]. Defaults to True.
backend (str, optional) – specifies the backend to be used (numpy or torch or warp). Defaults to numpy.
device (Optional[str], optional) – specifies the device to be used if running on the gpu with torch or warp backend.
Example:
>>> from omni.isaac.core import SimulationContext >>> >>> simulation_context = SimulationContext() >>> simulation_context <omni.isaac.core.simulation_context.simulation_context.SimulationContext object at 0x...>
- add_physics_callback(callback_name: str, callback_fn: Callable[[float], None]) None
Add a callback which will be called before each physics step.
callback_fn
should take a float argument (e.g.,step_size
)- Parameters
callback_name (str) – should be unique.
callback_fn (Callable[[float], None]) – [description]
Example:
>>> def callback_physics(step_size): ... print("physics callback -> step_size:", step_size) ... >>> simulation_context.add_physics_callback("callback_physics", callback_physics)
- add_render_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each rendering event such as .render().
callback_fn
should take an argument of type (e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable) – [description]
Example:
>>> def callback_render(event): ... print("render callback -> event:", event) ... >>> simulation_context.add_render_callback("callback_render", callback_render)
- add_stage_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each stage event such as open/close among others
callback_fn
should take an argument of typeomni.usd.StageEvent
(e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable[[omni.usd.StageEvent], None]) – [description]
Example:
>>> def callback_stage(event): ... print("stage callback -> event:", event) ... >>> simulation_context.add_stage_callback("callback_stage", callback_stage)
- add_timeline_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each timeline event such as play/pause.
callback_fn
should take an argument of typeomni.timeline.TimelineEvent
(e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable[[omni.timeline.TimelineEvent], None]) – [description]
Example:
>>> def callback_timeline(event): ... print("timeline callback -> event:", event) ... >>> simulation_context.add_timeline_callback("callback_timeline", callback_timeline)
- property app: omni.kit.app.IApp
- Returns
Omniverse Kit Application interface
- Return type
omni.kit.app.IApp
Example:
>>> simulation_context.app <omni.kit.app._app.IApp object at 0x...>
- property backend: str
- Returns
current backend. Supported backends are:
"numpy"
,"torch"
and"warp"
- Return type
str
Example:
>>> simulation_context.backend numpy
- property backend_utils
Get the current backend utils module
Backend
Utils module
"numpy"
omni.isaac.core.utils.numpy
"torch"
omni.isaac.core.utils.torch
"warp"
omni.isaac.core.utils.warp
- Returns
current backend utils module
- Return type
str
Example:
>>> simulation_context.backend_utils <module 'omni.isaac.core.utils.numpy'>
- clear() None
Clear the current stage leaving the PhysicsScene and /World
Example:
>>> simulation_context.clear()
- clear_all_callbacks() None
Clear all callbacks which were added using any
add_*_callback
methodExample:
>>> simulation_context.clear_render_callbacks()
- classmethod clear_instance() None
Delete the simulation context object, if it was instantiated before, and destroy any subscribed callback
Example:
>>> SimulationContext.clear_instance()
- clear_physics_callbacks() None
Remove all registered physics callbacks
Example:
>>> simulation_context.clear_physics_callbacks()
- clear_render_callbacks() None
Remove all registered render callbacks
Example:
>>> simulation_context.clear_render_callbacks()
- clear_stage_callbacks() None
Remove all registered stage callbacks
Example:
>>> simulation_context.clear_stage_callbacks()
- clear_timeline_callbacks() None
Remove all registered timeline callbacks
Example:
>>> simulation_context.clear_timeline_callbacks()
- property current_time: float
- Returns
current time (simulated physical time) that have elapsed since the simulation was played
- Return type
float
Example:
>>> # given a running Isaac Sim instance and after 911 physics steps at 60 Hz >>> simulation_context.current_time 15.183334125205874
- property current_time_step_index: int
- Returns
current number of physics steps that have elapsed since the simulation was played
- Return type
int
Example:
>>> # given a running Isaac Sim instance and after approximately 15 seconds of physics simulation at 60 Hz >>> simulation_context.current_time_step_index 911
- property device: str
- Returns
Device used by the physics context. None for numpy backend
- Return type
str
Example:
>>> simulation_context.device None
- get_block_on_render() bool
Get the block on render flag for the simulation thread
- Returns
True if one frame lag between any data captured from the render products and the current USD stage is guaranteed by blocking the step call.
- Return type
bool
Example:
>>> simulation_context.get_block_on_render() False
- get_physics_context() omni.isaac.core.physics_context.physics_context.PhysicsContext
Get the physics context (a class to deal with a physics scene and its settings) instance
- Raises
Exception – if there is no stage currently opened
- Returns
physics context object
- Return type
Example:
>>> simulation_context.get_physics_context() <omni.isaac.core.physics_context.physics_context.PhysicsContext object at 0x...>
- get_physics_dt() float
Get the current physics dt of the physics context
- Raises
Exception – if there is no stage currently opened
- Returns
current physics dt of the PhysicsContext
- Return type
float
Example:
>>> simulation_context.get_physics_dt() 0.016666666666666666
- get_rendering_dt() float
Get the current rendering dt
- Raises
Exception – if there is no stage currently opened
- Returns
current rendering dt
- Return type
float
Example:
>>> simulation_context.get_rendering_dt() 0.016666666666666666
- initialize_physics() None
Initialize the physics simulation view
Example:
>>> simulation_context.initialize_physics()
- async initialize_simulation_context_async() None
Initialize the simulation context
Hint
This method is intended to be used in the Isaac Sim’s Extensions workflow where the Kit application has the control over timing of physics and rendering steps
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.initialize_simulation_context_async() ... >>> run_coroutine(task())
- classmethod instance() omni.isaac.core.simulation_context.simulation_context.SimulationContext
Get the instance of the class, if it was instantiated before
- Returns
SimulationContext object or None
- Return type
Example:
>>> # given that the class has already been instantiated before >>> simulation_context = SimulationContext.instance() >>> simulation_context <omni.isaac.core.simulation_context.simulation_context.SimulationContext object at 0x...>
- is_playing() bool
Check whether the simulation is playing
- Returns
True if the simulator is playing.
- Return type
bool
Example:
>>> # given a simulation in play >>> simulation_context.is_playing() True
- is_simulating() bool
Check whether the simulation is running or not
Warning
With deprecation of Dynamic Control Toolbox, this function is not needed
It can return True if start_simulation is called even if play was pressed/called.
- Returns
bool” True if physics simulation is happening.
Example:
>>> # given a running simulation >>> simulation_context.is_simulating() True
- is_stopped() bool
Check whether the simulation is playing
- Returns
True if the simulator is stopped.
- Return type
bool
Example:
>>> # given a simulation in play >>> simulation_context.is_stopped() False
- pause() None
Pause the physics simulation
Example:
>>> simulation_context.pause()
- async pause_async() None
Pause the physics simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.pause_async() ... >>> run_coroutine(task())
- physics_callback_exists(callback_name: str) bool
Check if a physics callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_physics' >>> simulation_context.physics_callback_exists("callback_physics") True
- property physics_sim_view
Note
The physics simulation view instance will be only available after initializing the physics (see
initialize_physics
) or resetting the simulation context (seereset
)- Returns
Physics simulation view instance
- Return type
Example:
>>> simulation_context.physics_sim_view <omni.physics.tensors.impl.api.SimulationView object at 0x...>
- play() None
Start playing simulation
Note
It does one step internally to propagate all physics handles properly.
Example:
>>> simulation_context.play()
- async play_async() None
Start playing simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.play_async() ... >>> run_coroutine(task())
- remove_physics_callback(callback_name: str) None
Remove a physics callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_physics' >>> simulation_context.remove_physics_callback("callback_physics")
- remove_render_callback(callback_name: str) None
Remove a render callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_render' >>> simulation_context.remove_render_callback("callback_render")
- remove_stage_callback(callback_name: str) None
Remove a stage callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_stage' >>> simulation_context.remove_stage_callback("callback_stage")
- remove_timeline_callback(callback_name: str) None
Remove a timeline callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'timeline' >>> simulation_context.timeline_callback("timeline")
- render() None
Refresh the Isaac Sim app rendering components including UI elements, viewports and others
Warning
This method is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps
Example:
>>> simulation_context.render()
- async render_async() None
Refresh the Isaac Sim app rendering components including UI elements, viewports and others
Hint
This method is intended to be used in the Isaac Sim’s Extensions workflow where the Kit application has the control over timing of physics and rendering steps
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.render_async() ... >>> run_coroutine(task())
- render_callback_exists(callback_name: str) bool
Check if a render callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_render' >>> simulation_context.render_callback_exists("callback_render") True
- reset(soft: bool = False) None
Reset the physics simulation view.
Warning
This method is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps. For the Extensions workflow use the
reset_async
method instead- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> simulation_context.reset()
- async reset_async(soft: bool = False) None
Reset the physics simulation view (asynchronous version).
- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): >>> await simulation_context.reset_async() >>> >>> run_coroutine(task())
- set_block_on_render(block: bool) None
Set block on render flag for the simulation thread
Note
This guarantee a one frame lag between any data captured from the render products and the current USD stage if enabled.
- Parameters
block (bool) – True to block the thread until the renderer is done.
Example:
>>> simulation_context.set_block_on_render(False)
- set_simulation_dt(physics_dt: Optional[float] = None, rendering_dt: Optional[float] = None) None
Specify the physics step and rendering step size to use when stepping and rendering.
- Parameters
physics_dt (float) – The physics time-step. None means it won’t change the current setting. (default: None).
rendering_dt (float) – The rendering time-step. None means it won’t change the current setting. (default: None)
Hint
It is recommended that the two values be divisible, with the
rendering_dt
being equal to or greater than thephysics_dt
Example:
>>> set physics dt to 120 Hz and rendering dt to 60Hz (2 physics steps for each rendering) >>> simulation_context.set_simulation_dt(physics_dt=1.0 / 120.0, rendering_dt=1.0 / 60.0)
- property stage: pxr.Usd.Stage
- Returns
current open USD stage
- Return type
Usd.Stage
Example:
>>> simulation_context.stage Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x...:World....usd'), sessionLayer=Sdf.Find('anon:0x...:World...-session.usda'), pathResolverContext=<invalid repr>)
- stage_callback_exists(callback_name: str) bool
Check if a stage callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_stage' >>> simulation_context.stage_callback_exists("callback_stage") True
- step(render: bool = True) None
Steps the physics simulation while rendering or without.
Warning
Calling this method with the
render
parameter set to True (default value) is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps- Parameters
render (bool, optional) – Set to False to only do a physics simulation without rendering. Note: app UI will be frozen (since its not rendering) in this case. Defaults to True.
- Raises
Exception – if there is no stage currently opened
Example:
>>> simulation_context.step()
- stop() None
Stop the physics simulation
Example:
>>> simulation_context.stop()
- async stop_async() None
Stop the physics simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.stop_async() ... >>> run_coroutine(task())
- timeline_callback_exists(callback_name: str) bool
Check if a timeline callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_timeline' >>> simulation_context.timeline_callback_exists("callback_timeline") True
World
- class World(*args, **kwargs)
This class inherits from SimulationContext which provides the following.
SimulationContext provide functions that take care of many time-related events such as perform a physics or a render step for instance. Adding/ removing callback functions that gets triggered with certain events such as a physics step, timeline event (pause or play..etc), stage open/ close..etc.
It also includes an instance of PhysicsContext which takes care of many physics related settings such as setting physics dt, solver type..etc.
In addition to what is provided from SimulationContext, this class allows the user to add a task to the world and it contains a scene object.
To control the default reset state of different objects easily, the object could be added to a Scene. Besides this, the object is bound to a short keyword that facilitates objects retrievals, like in a dict.
Checkout the required tutorials at https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html
- Parameters
physics_dt (Optional[float], optional) – dt between physics steps. Defaults to None.
rendering_dt (Optional[float], optional) – dt between rendering steps. Note: rendering means rendering a frame of the current application and not only rendering a frame to the viewports/ cameras. So UI elements of Isaac Sim will be refreshed with this dt as well if running non-headless. Defaults to None.
stage_units_in_meters (Optional[float], optional) – The metric units of assets. This will affect gravity value..etc. Defaults to None.
physics_prim_path (Optional[str], optional) – specifies the prim path to create a PhysicsScene at, only in the case where no PhysicsScene already defined. Defaults to “/physicsScene”.
set_defaults (bool, optional) – set to True to use the defaults settings [physics_dt = 1.0/ 60.0, stage units in meters = 0.01 (i.e in cms), rendering_dt = 1.0 / 60.0, gravity = -9.81 m / s ccd_enabled, stabilization_enabled, gpu dynamics turned off, broadcast type is MBP, solver type is TGS]. Defaults to True.
backend (str, optional) – specifies the backend to be used (numpy or torch or warp). Defaults to numpy.
device (Optional[str], optional) – specifies the device to be used if running on the gpu with torch or warp backends.
Example:
>>> from omni.isaac.core import World >>> >>> world = World() >>> world <omni.isaac.core.world.world.World object at 0x...>
- add_physics_callback(callback_name: str, callback_fn: Callable[[float], None]) None
Add a callback which will be called before each physics step.
callback_fn
should take a float argument (e.g.,step_size
)- Parameters
callback_name (str) – should be unique.
callback_fn (Callable[[float], None]) – [description]
Example:
>>> def callback_physics(step_size): ... print("physics callback -> step_size:", step_size) ... >>> simulation_context.add_physics_callback("callback_physics", callback_physics)
- add_render_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each rendering event such as .render().
callback_fn
should take an argument of type (e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable) – [description]
Example:
>>> def callback_render(event): ... print("render callback -> event:", event) ... >>> simulation_context.add_render_callback("callback_render", callback_render)
- add_stage_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each stage event such as open/close among others
callback_fn
should take an argument of typeomni.usd.StageEvent
(e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable[[omni.usd.StageEvent], None]) – [description]
Example:
>>> def callback_stage(event): ... print("stage callback -> event:", event) ... >>> simulation_context.add_stage_callback("callback_stage", callback_stage)
- add_task(task: omni.isaac.core.tasks.base_task.BaseTask) None
Add a task to the task registry
Note
Tasks should have a unique name
- Parameters
task (BaseTask) – task object
Example:
>>> from omni.isaac.core.tasks import BaseTask >>> >>> class Task(BaseTask): ... def get_observations(self): ... return {'obs': [0]} ... ... def calculate_metrics(self): ... return {"reward": 1} ... ... def is_done(self): ... return False ... >>> task = Task(name="custom_task") >>> world.add_task(task)
- add_timeline_callback(callback_name: str, callback_fn: Callable) None
Add a callback which will be called after each timeline event such as play/pause.
callback_fn
should take an argument of typeomni.timeline.TimelineEvent
(e.g.,event
)- Parameters
callback_name (str) – [description]
callback_fn (Callable[[omni.timeline.TimelineEvent], None]) – [description]
Example:
>>> def callback_timeline(event): ... print("timeline callback -> event:", event) ... >>> simulation_context.add_timeline_callback("callback_timeline", callback_timeline)
- property app: omni.kit.app.IApp
- Returns
Omniverse Kit Application interface
- Return type
omni.kit.app.IApp
Example:
>>> simulation_context.app <omni.kit.app._app.IApp object at 0x...>
- property backend: str
- Returns
current backend. Supported backends are:
"numpy"
,"torch"
and"warp"
- Return type
str
Example:
>>> simulation_context.backend numpy
- property backend_utils
Get the current backend utils module
Backend
Utils module
"numpy"
omni.isaac.core.utils.numpy
"torch"
omni.isaac.core.utils.torch
"warp"
omni.isaac.core.utils.warp
- Returns
current backend utils module
- Return type
str
Example:
>>> simulation_context.backend_utils <module 'omni.isaac.core.utils.numpy'>
- calculate_metrics(task_name: Optional[str] = None) None
Get metrics from all the tasks that were added
- Parameters
task_name (Optional[str], optional) – task name to ask for. Defaults to None, which means all the tasks
- Returns
the computed task (or all tasks) metric
- Return type
dict
Example:
>>> world.calculate_metrics("custom_task") {'reward': 1}
- clear() None
Clear the current stage leaving the PhysicsScene and /World
Example:
>>> world.clear()
- clear_all_callbacks() None
Clear all callbacks which were added using any
add_*_callback
methodExample:
>>> simulation_context.clear_render_callbacks()
- classmethod clear_instance()
Delete the world object, if it was instantiated before, and destroy any subscribed callback
Example:
>>> World.clear_instance()
- clear_physics_callbacks() None
Remove all registered physics callbacks
Example:
>>> simulation_context.clear_physics_callbacks()
- clear_render_callbacks() None
Remove all registered render callbacks
Example:
>>> simulation_context.clear_render_callbacks()
- clear_stage_callbacks() None
Remove all registered stage callbacks
Example:
>>> simulation_context.clear_stage_callbacks()
- clear_timeline_callbacks() None
Remove all registered timeline callbacks
Example:
>>> simulation_context.clear_timeline_callbacks()
- property current_time: float
- Returns
current time (simulated physical time) that have elapsed since the simulation was played
- Return type
float
Example:
>>> # given a running Isaac Sim instance and after 911 physics steps at 60 Hz >>> simulation_context.current_time 15.183334125205874
- property current_time_step_index: int
- Returns
current number of physics steps that have elapsed since the simulation was played
- Return type
int
Example:
>>> # given a running Isaac Sim instance and after approximately 15 seconds of physics simulation at 60 Hz >>> simulation_context.current_time_step_index 911
- property device: str
- Returns
Device used by the physics context. None for numpy backend
- Return type
str
Example:
>>> simulation_context.device None
- get_block_on_render() bool
Get the block on render flag for the simulation thread
- Returns
True if one frame lag between any data captured from the render products and the current USD stage is guaranteed by blocking the step call.
- Return type
bool
Example:
>>> simulation_context.get_block_on_render() False
- get_current_tasks() List[omni.isaac.core.tasks.base_task.BaseTask]
Get a dictionary of the registered tasks where keys are task names
- Returns
registered tasks
- Return type
List[BaseTask]
Example:
>>> world.get_current_tasks() {'custom_task': <custom.task.scripts.extension.Task object at 0x...>}
- get_data_logger() omni.isaac.core.loggers.data_logger.DataLogger
Return the data logger of the world.
- Returns
data logger instance
- Return type
Example:
>>> world.get_data_logger() <omni.isaac.core.loggers.data_logger.DataLogger object at 0x...>
- get_observations(task_name: Optional[str] = None) dict
Get observations from all the tasks that were added
- Parameters
task_name (Optional[str], optional) – task name to ask for. Defaults to None, which means all the tasks
- Returns
the task (or all tasks) observations
- Return type
dict
Example:
>>> world.get_observations("custom_task") {'obs': [0]}
- get_physics_context() omni.isaac.core.physics_context.physics_context.PhysicsContext
Get the physics context (a class to deal with a physics scene and its settings) instance
- Raises
Exception – if there is no stage currently opened
- Returns
physics context object
- Return type
Example:
>>> simulation_context.get_physics_context() <omni.isaac.core.physics_context.physics_context.PhysicsContext object at 0x...>
- get_physics_dt() float
Get the current physics dt of the physics context
- Raises
Exception – if there is no stage currently opened
- Returns
current physics dt of the PhysicsContext
- Return type
float
Example:
>>> simulation_context.get_physics_dt() 0.016666666666666666
- get_rendering_dt() float
Get the current rendering dt
- Raises
Exception – if there is no stage currently opened
- Returns
current rendering dt
- Return type
float
Example:
>>> simulation_context.get_rendering_dt() 0.016666666666666666
- get_task(name: str) omni.isaac.core.tasks.base_task.BaseTask
Get a task by its name
Example:
>>> world.get_task("custom_task") <custom.task.scripts.extension.Task object at 0x...>
- initialize_physics() None
Initialize the physics simulation view and each added object to the Scene
Example:
>>> world.initialize_physics()
- async initialize_simulation_context_async() None
Initialize the simulation context
Hint
This method is intended to be used in the Isaac Sim’s Extensions workflow where the Kit application has the control over timing of physics and rendering steps
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.initialize_simulation_context_async() ... >>> run_coroutine(task())
- classmethod instance() omni.isaac.core.simulation_context.simulation_context.SimulationContext
Get the instance of the class, if it was instantiated before
- Returns
SimulationContext object or None
- Return type
Example:
>>> # given that the class has already been instantiated before >>> simulation_context = SimulationContext.instance() >>> simulation_context <omni.isaac.core.simulation_context.simulation_context.SimulationContext object at 0x...>
- is_done(task_name: Optional[str] = None) bool
Get done from all the tasks that were added
- Parameters
task_name (Optional[str], optional) – task name to ask for. Defaults to None, which means all the tasks
- Returns
whether the task (or all tasks) is done
- Return type
bool
Example:
>>> world.is_done("custom_task") False
- is_playing() bool
Check whether the simulation is playing
- Returns
True if the simulator is playing.
- Return type
bool
Example:
>>> # given a simulation in play >>> simulation_context.is_playing() True
- is_simulating() bool
Check whether the simulation is running or not
Warning
With deprecation of Dynamic Control Toolbox, this function is not needed
It can return True if start_simulation is called even if play was pressed/called.
- Returns
bool” True if physics simulation is happening.
Example:
>>> # given a running simulation >>> simulation_context.is_simulating() True
- is_stopped() bool
Check whether the simulation is playing
- Returns
True if the simulator is stopped.
- Return type
bool
Example:
>>> # given a simulation in play >>> simulation_context.is_stopped() False
- is_tasks_scene_built() bool
Check if the
set_up_scene
method was called for each registered taskExample:
>>> # given a world instance that was rested at some point >>> world.is_tasks_scene_built() True
- pause() None
Pause the physics simulation
Example:
>>> simulation_context.pause()
- async pause_async() None
Pause the physics simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.pause_async() ... >>> run_coroutine(task())
- physics_callback_exists(callback_name: str) bool
Check if a physics callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_physics' >>> simulation_context.physics_callback_exists("callback_physics") True
- property physics_sim_view
Note
The physics simulation view instance will be only available after initializing the physics (see
initialize_physics
) or resetting the simulation context (seereset
)- Returns
Physics simulation view instance
- Return type
Example:
>>> simulation_context.physics_sim_view <omni.physics.tensors.impl.api.SimulationView object at 0x...>
- play() None
Start playing simulation
Note
It does one step internally to propagate all physics handles properly.
Example:
>>> simulation_context.play()
- async play_async() None
Start playing simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.play_async() ... >>> run_coroutine(task())
- remove_physics_callback(callback_name: str) None
Remove a physics callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_physics' >>> simulation_context.remove_physics_callback("callback_physics")
- remove_render_callback(callback_name: str) None
Remove a render callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_render' >>> simulation_context.remove_render_callback("callback_render")
- remove_stage_callback(callback_name: str) None
Remove a stage callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'callback_stage' >>> simulation_context.remove_stage_callback("callback_stage")
- remove_timeline_callback(callback_name: str) None
Remove a timeline callback by its name
- Parameters
callback_name (str) – callback name
Example:
>>> # given a registered callback named 'timeline' >>> simulation_context.timeline_callback("timeline")
- render() None
Refresh the Isaac Sim app rendering components including UI elements, viewports and others
Warning
This method is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps
Example:
>>> simulation_context.render()
- async render_async() None
Refresh the Isaac Sim app rendering components including UI elements, viewports and others
Hint
This method is intended to be used in the Isaac Sim’s Extensions workflow where the Kit application has the control over timing of physics and rendering steps
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.render_async() ... >>> run_coroutine(task())
- render_callback_exists(callback_name: str) bool
Check if a render callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_render' >>> simulation_context.render_callback_exists("callback_render") True
- reset(soft: bool = False) None
- Reset the stage to its initial state and each object included in the Scene to its default state
as specified by the
set_default_state
and__init__
methods
Note
All tasks should be added before the first reset is called unless the
clear
method was called.All articulations should be added before the first reset is called unless the
clear
method was called.This method takes care of initializing articulation handles with the first reset called.
This will do one step internally regardless
Call
post_reset
on each object in the SceneCall
post_reset
on each Task
Things like setting PD gains for instance should happen at a Task reset or a Robot reset since the defaults are restored after
stop
method is called.Warning
This method is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps. For the Extensions workflow use the
reset_async
method instead- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> world.reset()
- async reset_async(soft: bool = False) None
- Reset the stage to its initial state and each object included in the Scene to its default state
as specified by the
set_default_state
and__init__
methods
Note
All tasks should be added before the first reset is called unless the
clear
method was called.All articulations should be added before the first reset is called unless the
clear
method was called.This method takes care of initializing articulation handles with the first reset called.
This will do one step internally regardless
Call
post_reset
on each object in the SceneCall
post_reset
on each Task
Things like setting PD gains for instance should happen at a Task reset or a Robot reset since the defaults are restored after
stop
method is called.- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await world.reset_async() ... >>> run_coroutine(task())
- async reset_async_no_set_up_scene(soft: bool = False) None
- Reset the stage to its initial state and each object included in the Scene to its default state
as specified by the
set_default_state
and__init__
methods
Note
All tasks should be added before the first reset is called unless the
clear
method was called.All articulations should be added before the first reset is called unless the
clear
method was called.This method takes care of initializing articulation handles with the first reset called.
This will do one step internally regardless
Call
post_reset
on each object in the SceneCall
post_reset
on each Task
Things like setting PD gains for instance should happen at a Task reset or a Robot reset since the defaults are restored after
stop
method is called.- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): >>> await world.reset_async_no_set_up_scene() >>> >>> run_coroutine(task())
- async reset_async_set_up_scene(soft: bool = False) None
- Reset the stage to its initial state and each object included in the Scene to its default state
as specified by the
set_default_state
and__init__
methods
Note
All tasks should be added before the first reset is called unless the
clear
method was called.All articulations should be added before the first reset is called unless the
clear
method was called.This method takes care of initializing articulation handles with the first reset called.
This will do one step internally regardless
Call
post_reset
on each object in the SceneCall
post_reset
on each Task
Things like setting PD gains for instance should happen at a Task reset or a Robot reset since the defaults are restored after
stop
method is called.- Parameters
soft (bool, optional) – if set to True simulation won’t be stopped and start again. It only calls the reset on the scene objects.
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): >>> await world.reset_async_set_up_scene() >>> >>> run_coroutine(task())
- property scene: omni.isaac.core.scenes.scene.Scene
- Returns
Scene instance
- Return type
Example:
>>> world.scene <omni.isaac.core.scenes.scene.Scene object at 0x>
- set_block_on_render(block: bool) None
Set block on render flag for the simulation thread
Note
This guarantee a one frame lag between any data captured from the render products and the current USD stage if enabled.
- Parameters
block (bool) – True to block the thread until the renderer is done.
Example:
>>> simulation_context.set_block_on_render(False)
- set_simulation_dt(physics_dt: Optional[float] = None, rendering_dt: Optional[float] = None) None
Specify the physics step and rendering step size to use when stepping and rendering.
- Parameters
physics_dt (float) – The physics time-step. None means it won’t change the current setting. (default: None).
rendering_dt (float) – The rendering time-step. None means it won’t change the current setting. (default: None)
Hint
It is recommended that the two values be divisible, with the
rendering_dt
being equal to or greater than thephysics_dt
Example:
>>> set physics dt to 120 Hz and rendering dt to 60Hz (2 physics steps for each rendering) >>> simulation_context.set_simulation_dt(physics_dt=1.0 / 120.0, rendering_dt=1.0 / 60.0)
- property stage: pxr.Usd.Stage
- Returns
current open USD stage
- Return type
Usd.Stage
Example:
>>> simulation_context.stage Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x...:World....usd'), sessionLayer=Sdf.Find('anon:0x...:World...-session.usda'), pathResolverContext=<invalid repr>)
- stage_callback_exists(callback_name: str) bool
Check if a stage callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_stage' >>> simulation_context.stage_callback_exists("callback_stage") True
- step(render: bool = True, step_sim: bool = True) None
Step the physics simulation while rendering or without.
Note
The
pre_step
for each task is called before stepping. This method also update the Bounding Box Cache time for computing bounding box if enabledWarning
Calling this method with the
render
parameter set to True (default value) is not intended to be used in the Isaac Sim’s Extensions workflow since the Kit application has the control over the rendering steps- Parameters
render (bool, optional) – Set to False to only do a physics simulation without rendering. Note: app UI will be frozen (since its not rendering) in this case. Defaults to True.
step_sim (bool) – True to step simulation (physics and/or rendering)
Example:
>>> world.step()
- step_async(step_size: Optional[float] = None) None
Call all functions that should be called pre stepping the physics
Note
The
pre_step
for each task is called before stepping. This method also update the Bounding Box Cache time for computing bounding box if enabled- Parameters
step_size (float) – step size
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await world.step_async() ... >>> run_coroutine(task())
- stop() None
Stop the physics simulation
Example:
>>> simulation_context.stop()
- async stop_async() None
Stop the physics simulation
Example:
>>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await simulation_context.stop_async() ... >>> run_coroutine(task())
- timeline_callback_exists(callback_name: str) bool
Check if a timeline callback exists
- Parameters
callback_name (str) – callback name
- Returns
whether the callback is registered
- Return type
bool
Example:
>>> # given a registered callback named 'callback_timeline' >>> simulation_context.timeline_callback_exists("callback_timeline") True
Tasks
Base Task
- class BaseTask(name: str, offset: Optional[numpy.ndarray] = None)
This class provides a way to set up a task in a scene and modularize adding objects to stage, getting observations needed for the behavioral layer, calculating metrics needed about the task, calling certain things pre-stepping, creating multiple tasks at the same time and much more.
Checkout the required tutorials at https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html
- Parameters
name (str) – needs to be unique if added to the World.
offset (Optional[np.ndarray], optional) – offset applied to all assets of the task.
- calculate_metrics() dict
[summary]
- Raises
NotImplementedError – [description]
- cleanup() None
Called before calling a reset() on the world to removed temporary objects that were added during simulation for instance.
- property device
- get_description() str
[summary]
- Returns
[description]
- Return type
str
- get_observations() dict
Returns current observations from the objects needed for the behavioral layer.
- Raises
NotImplementedError – [description]
- Returns
[description]
- Return type
dict
- get_params() dict
- Gets the parameters of the task.
This is defined differently for each task in order to access the task’s objects and values. Note that this is different from get_observations. Things like the robot name, block name..etc can be defined here for faster retrieval. should have the form of params_representation[“param_name”] = {“value”: param_value, “modifiable”: bool}
- Raises
NotImplementedError – [description]
- Returns
defined parameters of the task.
- Return type
dict
- get_task_objects() dict
[summary]
- Returns
[description]
- Return type
dict
- is_done() bool
Returns True of the task is done.
- Raises
NotImplementedError – [description]
- property name: str
[summary]
- Returns
[description]
- Return type
str
- post_reset() None
Calls while doing a .reset() on the world.
- pre_step(time_step_index: int, simulation_time: float) None
called before stepping the physics simulation.
- Parameters
time_step_index (int) – [description]
simulation_time (float) – [description]
- property scene: omni.isaac.core.scenes.scene.Scene
Scene of the world
- Returns
[description]
- Return type
- set_params(*args, **kwargs) None
Changes the modifiable parameters of the task
- Raises
NotImplementedError – [description]
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
- Adding assets to the stage as well as adding the encapsulated objects such as XFormPrim..etc
to the task_objects happens here.
- Parameters
scene (Scene) – [description]
Follow Target
- class FollowTarget(name: str, target_prim_path: Optional[str] = None, target_name: Optional[str] = None, target_position: Optional[numpy.ndarray] = None, target_orientation: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None)
[summary]
- Parameters
name (str) – [description]
target_prim_path (Optional[str], optional) – [description]. Defaults to None.
target_name (Optional[str], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
- add_obstacle(position: Optional[numpy.ndarray] = None)
[summary]
- Parameters
position (np.ndarray, optional) – [description]. Defaults to np.array([0.1, 0.1, 1.0]).
- calculate_metrics() dict
[summary]
- cleanup() None
[summary]
- property device
- get_description() str
[summary]
- Returns
[description]
- Return type
str
- get_observations() dict
[summary]
- Returns
[description]
- Return type
dict
- get_obstacle_to_delete() None
[summary]
- Returns
[description]
- Return type
[type]
- get_params() dict
[summary]
- Returns
[description]
- Return type
dict
- get_task_objects() dict
[summary]
- Returns
[description]
- Return type
dict
- is_done() bool
[summary]
- property name: str
[summary]
- Returns
[description]
- Return type
str
- obstacles_exist() bool
[summary]
- Returns
[description]
- Return type
bool
- post_reset() None
[summary]
- pre_step(time_step_index: int, simulation_time: float) None
[summary]
- Parameters
time_step_index (int) – [description]
simulation_time (float) – [description]
- remove_obstacle(name: Optional[str] = None) None
[summary]
- Parameters
name (Optional[str], optional) – [description]. Defaults to None.
- property scene: omni.isaac.core.scenes.scene.Scene
Scene of the world
- Returns
[description]
- Return type
- set_params(target_prim_path: Optional[str] = None, target_name: Optional[str] = None, target_position: Optional[numpy.ndarray] = None, target_orientation: Optional[numpy.ndarray] = None) None
[summary]
- Parameters
target_prim_path (Optional[str], optional) – [description]. Defaults to None.
target_name (Optional[str], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
- abstract set_robot() None
[summary]
- Raises
NotImplementedError – [description]
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
[summary]
- Parameters
scene (Scene) – [description]
- target_reached() bool
[summary]
- Returns
[description]
- Return type
bool
Pick and Place
- class PickPlace(name: str, cube_initial_position: Optional[numpy.ndarray] = None, cube_initial_orientation: Optional[numpy.ndarray] = None, target_position: Optional[numpy.ndarray] = None, cube_size: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None)
[summary]
- Parameters
name (str) – [description]
cube_initial_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_initial_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_size (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
- calculate_metrics() dict
[summary]
- cleanup() None
Called before calling a reset() on the world to removed temporary objects that were added during simulation for instance.
- property device
- get_description() str
[summary]
- Returns
[description]
- Return type
str
- get_observations() dict
[summary]
- Returns
[description]
- Return type
dict
- get_params() dict
- Gets the parameters of the task.
This is defined differently for each task in order to access the task’s objects and values. Note that this is different from get_observations. Things like the robot name, block name..etc can be defined here for faster retrieval. should have the form of params_representation[“param_name”] = {“value”: param_value, “modifiable”: bool}
- Raises
NotImplementedError – [description]
- Returns
defined parameters of the task.
- Return type
dict
- get_task_objects() dict
[summary]
- Returns
[description]
- Return type
dict
- is_done() bool
[summary]
- property name: str
[summary]
- Returns
[description]
- Return type
str
- post_reset() None
Calls while doing a .reset() on the world.
- pre_step(time_step_index: int, simulation_time: float) None
[summary]
- Parameters
time_step_index (int) – [description]
simulation_time (float) – [description]
- property scene: omni.isaac.core.scenes.scene.Scene
Scene of the world
- Returns
[description]
- Return type
- set_params(cube_position: Optional[numpy.ndarray] = None, cube_orientation: Optional[numpy.ndarray] = None, target_position: Optional[numpy.ndarray] = None) None
Changes the modifiable parameters of the task
- Raises
NotImplementedError – [description]
- abstract set_robot() None
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
[summary]
- Parameters
scene (Scene) – [description]
Stacking
- class Stacking(name: str, cube_initial_positions: numpy.ndarray, cube_initial_orientations: Optional[numpy.ndarray] = None, stack_target_position: Optional[numpy.ndarray] = None, cube_size: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None)
[summary]
- Parameters
name (str) – [description]
cube_initial_positions (np.ndarray) – [description]
cube_initial_orientations (Optional[np.ndarray], optional) – [description]. Defaults to None.
stack_target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_size (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
- calculate_metrics() dict
[summary]
- Raises
NotImplementedError – [description]
- Returns
[description]
- Return type
dict
- cleanup() None
Called before calling a reset() on the world to removed temporary objects that were added during simulation for instance.
- property device
- get_cube_names() List[str]
[summary]
- Returns
[description]
- Return type
List[str]
- get_description() str
[summary]
- Returns
[description]
- Return type
str
- get_observations() dict
[summary]
- Returns
[description]
- Return type
dict
- get_params() dict
[summary]
- Returns
[description]
- Return type
dict
- get_task_objects() dict
[summary]
- Returns
[description]
- Return type
dict
- is_done() bool
[summary]
- Raises
NotImplementedError – [description]
- Returns
[description]
- Return type
bool
- property name: str
[summary]
- Returns
[description]
- Return type
str
- post_reset() None
[summary]
- pre_step(time_step_index: int, simulation_time: float) None
[summary]
- Parameters
time_step_index (int) – [description]
simulation_time (float) – [description]
- property scene: omni.isaac.core.scenes.scene.Scene
Scene of the world
- Returns
[description]
- Return type
- set_params(cube_name: Optional[str] = None, cube_position: Optional[str] = None, cube_orientation: Optional[str] = None, stack_target_position: Optional[str] = None) None
[summary]
- Parameters
cube_name (Optional[str], optional) – [description]. Defaults to None.
cube_position (Optional[str], optional) – [description]. Defaults to None.
cube_orientation (Optional[str], optional) – [description]. Defaults to None.
stack_target_position (Optional[str], optional) – [description]. Defaults to None.
- abstract set_robot() None
[summary]
- Raises
NotImplementedError – [description]
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
[summary]
- Parameters
scene (Scene) – [description]
Utils
Bounds Utils
Utils for computing the Axis-Aligned Bounding Box (AABB) and the Oriented Bounding Box (OBB) of a prim.
The AABB is the smallest cuboid that can completely contain the prim it represents. It is defined by the following 3D coordinates: \((x_{min}, y_{min}, z_{min}, x_{max}, y_{max}, z_{max})\).
Unlike the AABB, which is aligned with the coordinate axes, the OBB can be oriented at any angle in 3D space.
- compute_aabb(bbox_cache: pxr.UsdGeom.BBoxCache, prim_path: str, include_children: bool = False) numpy.array
Compute an Axis-Aligned Bounding Box (AABB) for a given
prim_path
A combined AABB is computed if
include_children
is True- Parameters
bbox_cache (UsdGeom.BboxCache) – Existing Bounding box cache to use for computation
prim_path (str) – prim path to compute AABB for
include_children (bool, optional) – include children of specified prim in calculation. Defaults to False.
- Returns
Bounding box for this prim, [min x, min y, min z, max x, max y, max z]
- Return type
np.array
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> # 1 stage unit length cube centered at (0.0, 0.0, 0.0) >>> cache = bounds_utils.create_bbox_cache() >>> bounds_utils.compute_aabb(cache, prim_path="/World/Cube") [-0.5 -0.5 -0.5 0.5 0.5 0.5] >>> >>> # the same cube rotated 45 degrees around the z-axis >>> cache = bounds_utils.create_bbox_cache() >>> bounds_utils.compute_aabb(cache, prim_path="/World/Cube") [-0.70710678 -0.70710678 -0.5 0.70710678 0.70710678 0.5]
- compute_combined_aabb(bbox_cache: pxr.UsdGeom.BBoxCache, prim_paths: List[str]) numpy.array
Computes a combined Axis-Aligned Bounding Box (AABB) given a list of prim paths
- Parameters
bbox_cache (UsdGeom.BboxCache) – Existing Bounding box cache to use for computation
prim_paths (List[str]) – List of prim paths to compute combined AABB for
- Returns
Bounding box for input prims, [min x, min y, min z, max x, max y, max z]
- Return type
np.array
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> # 1 stage unit length cube centered at (0.0, 0.0, 0.0) >>> # with a 1 stage unit diameter sphere centered at (-0.5, 0.5, 0.5) >>> cache = bounds_utils.create_bbox_cache() >>> bounds_utils.compute_combined_aabb(cache, prim_paths=["/World/Cube", "/World/Sphere"]) [-1. -0.5 -0.5 0.5 1. 1. ]
- compute_obb(bbox_cache: pxr.UsdGeom.BBoxCache, prim_path: str) Tuple[numpy.ndarray, numpy.ndarray, numpy.ndarray]
Computes the Oriented Bounding Box (OBB) of a prim
Note
The OBB does not guarantee the smallest possible bounding box, it rotates and scales the default AABB.
The rotation matrix incorporates any scale factors applied to the object.
The half_extent values do not include these scaling effects.
- Parameters
bbox_cache (UsdGeom.BBoxCache) – USD Bounding Box Cache object to use for computation
prim_path (str) – Prim path to compute OBB for
- Returns
- A tuple containing the following OBB information:
The centroid of the OBB as a NumPy array.
The axes of the OBB as a 2D NumPy array, where each row represents a different axis.
The half extent of the OBB as a NumPy array.
- Return type
Tuple[np.ndarray, np.ndarray, np.ndarray]
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> # 1 stage unit length cube centered at (0.0, 0.0, 0.0) >>> cache = bounds_utils.create_bbox_cache() >>> centroid, axes, half_extent = bounds_utils.compute_obb(cache, prim_path="/World/Cube") >>> centroid [0. 0. 0.] >>> axes [[1. 0. 0.] [0. 1. 0.] [0. 0. 1.]] >>> half_extent [0.5 0.5 0.5] >>> >>> # the same cube rotated 45 degrees around the z-axis >>> cache = bounds_utils.create_bbox_cache() >>> centroid, axes, half_extent = bounds_utils.compute_obb(cache, prim_path="/World/Cube") >>> centroid [0. 0. 0.] >>> axes [[ 0.70710678 0.70710678 0. ] [-0.70710678 0.70710678 0. ] [ 0. 0. 1. ]] >>> half_extent [0.5 0.5 0.5]
- compute_obb_corners(bbox_cache: pxr.UsdGeom.BBoxCache, prim_path: str) numpy.ndarray
Computes the corners of the Oriented Bounding Box (OBB) of a prim
- Parameters
bbox_cache (UsdGeom.BBoxCache) – Bounding Box Cache object to use for computation
prim_path (str) – Prim path to compute OBB for
- Returns
NumPy array of shape (8, 3) containing each corner location of the OBB
\(c_0 = (x_{min}, y_{min}, z_{min})\)
\(c_1 = (x_{min}, y_{min}, z_{max})\)
\(c_2 = (x_{min}, y_{max}, z_{min})\)
\(c_3 = (x_{min}, y_{max}, z_{max})\)
\(c_4 = (x_{max}, y_{min}, z_{min})\)
\(c_5 = (x_{max}, y_{min}, z_{max})\)
\(c_6 = (x_{max}, y_{max}, z_{min})\)
\(c_7 = (x_{max}, y_{max}, z_{max})\)- Return type
np.ndarray
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> cache = bounds_utils.create_bbox_cache() >>> bounds_utils.compute_obb_corners(cache, prim_path="/World/Cube") [[-0.5 -0.5 -0.5] [-0.5 -0.5 0.5] [-0.5 0.5 -0.5] [-0.5 0.5 0.5] [ 0.5 -0.5 -0.5] [ 0.5 -0.5 0.5] [ 0.5 0.5 -0.5] [ 0.5 0.5 0.5]]
- create_bbox_cache(time: pxr.Usd.TimeCode = Usd.TimeCode.Default(), use_extents_hint: bool = True) pxr.UsdGeom.BBoxCache
Helper function to create a Bounding Box Cache object that can be used for computations
- Parameters
time (Usd.TimeCode, optional) – time at which cache should be initialized. Defaults to Usd.TimeCode.Default().
use_extents_hint (bool, optional) – Use existing extents attribute on prim to compute bounding box. Defaults to True.
- Returns
Initialized bbox cache
- Return type
UsdGeom.BboxCache
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> bounds_utils.create_bbox_cache() <pxr.UsdGeom.BBoxCache object at 0x7f6720b8bc90>
- get_obb_corners(centroid: numpy.ndarray, axes: numpy.ndarray, half_extent: numpy.ndarray) numpy.ndarray
Computes the corners of the Oriented Bounding Box (OBB) from the given OBB information
- Parameters
centroid (np.ndarray) – The centroid of the OBB as a NumPy array.
axes (np.ndarray) – The axes of the OBB as a 2D NumPy array, where each row represents a different axis.
half_extent (np.ndarray) – The half extent of the OBB as a NumPy array.
- Returns
NumPy array of shape (8, 3) containing each corner location of the OBB
\(c_0 = (x_{min}, y_{min}, z_{min})\)
\(c_1 = (x_{min}, y_{min}, z_{max})\)
\(c_2 = (x_{min}, y_{max}, z_{min})\)
\(c_3 = (x_{min}, y_{max}, z_{max})\)
\(c_4 = (x_{max}, y_{min}, z_{min})\)
\(c_5 = (x_{max}, y_{min}, z_{max})\)
\(c_6 = (x_{max}, y_{max}, z_{min})\)
\(c_7 = (x_{max}, y_{max}, z_{max})\)- Return type
np.ndarray
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> >>> cache = bounds_utils.create_bbox_cache() >>> centroid, axes, half_extent = bounds_utils.compute_obb(cache, prim_path="/World/Cube") >>> bounds_utils.get_obb_corners(centroid, axes, half_extent) [[-0.5 -0.5 -0.5] [-0.5 -0.5 0.5] [-0.5 0.5 -0.5] [-0.5 0.5 0.5] [ 0.5 -0.5 -0.5] [ 0.5 -0.5 0.5] [ 0.5 0.5 -0.5] [ 0.5 0.5 0.5]]
- recompute_extents(prim: pxr.UsdGeom.Boundable, time: pxr.Usd.TimeCode = Usd.TimeCode.Default(), include_children: bool = False) None
Recomputes and overwrites the extents attribute for a UsdGeom.Boundable prim
- Parameters
prim (UsdGeom.Boundable) – Input prim to recompute extents for
time (Usd.TimeCode, optional) – timecode to use for computing extents. Defaults to Usd.TimeCode.Default().
include_children (bool, optional) – include children of specified prim in calculation. Defaults to False.
- Raises
ValueError – If prim is not of UsdGeom.Boundable type
Example:
>>> import omni.isaac.core.utils.bounds as bounds_utils >>> import omni.isaac.core.utils.stage as stage_utils >>> >>> prim = stage_utils.get_current_stage().GetPrimAtPath("/World/Cube") >>> bounds_utils.recompute_extents(prim)
Carb Utils
Carb settings is a generalized subsystem designed to provide a simple to use interface to Kit’s various subsystems, which can be automated, enumerated, serialized and so on.
The most common types of settings are:
Persistent (saved between sessions):
"/persistent/<setting>"
(e.g.,"/persistent/physics/numThreads"
)Application:
"/app/<setting>"
(e.g.,"/app/viewport/grid/enabled"
)Extension:
"/exts/<extension>/<setting>"
(e.g.,"/exts/omni.kit.debug.python/host"
)
- get_carb_setting(carb_settings: carb.settings._settings.ISettings, setting: str) Any
Convenience function to get settings.
- Parameters
carb_settings (carb.settings.ISettings) – The interface to carb settings.
setting (str) – Name of setting to change.
- Returns
Value for the setting.
- Return type
Any
Example:
>>> import carb >>> import omni.isaac.core.utils.carb as carb_utils >>> >>> settings = carb.settings.get_settings() >>> carb_utils.get_carb_setting(settings, "/physics/updateToUsd") False
- set_carb_setting(carb_settings: carb.settings._settings.ISettings, setting: str, value: Any) None
Convenience to set the carb settings.
- Parameters
carb_settings (carb.settings.ISettings) – The interface to carb settings.
setting (str) – Name of setting to change.
value (Any) – New value for the setting.
- Raises
TypeError – If the type of value does not match setting type.
Example:
>>> import carb >>> import omni.isaac.core.utils.carb as carb_utils >>> >>> settings = carb.settings.get_settings() >>> carb_utils.set_carb_setting(settings, "/physics/updateToUsd", True)
Collisions Utils
- ray_cast(position: numpy.array, orientation: numpy.array, offset: numpy.array, max_dist: float = 100.0) Tuple[Union[None, str], float]
Projects a raycast forward along x axis with specified offset
If a hit is found within the maximum distance, then the object’s prim path and distance to it is returned. Otherwise, a None and 10000 is returned.
- Parameters
position (np.array) – origin’s position for ray cast
orientation (np.array) – origin’s orientation for ray cast
offset (np.array) – offset for ray cast
max_dist (float, optional) – maximum distance to test for collisions in stage units. Defaults to 100.0.
- Returns
path to geometry that was hit and hit distance, returns None, 10000 if no hit occurred
- Return type
Tuple[Union[None, str], float]
Constants Utils
- AXES_INDICES = {'X': 0, 'Y': 1, 'Z': 2, 'x': 0, 'y': 1, 'z': 2}
Mapping from axis name to axis ID
Example:
>>> import omni.isaac.core.utils.constants as constants_utils >>> >>> # get the x-axis index >>> constants_utils.AXES_INDICES['x'] 0 >>> constants_utils.AXES_INDICES['X'] 0
- AXES_TOKEN = {'X': 'X', 'Y': 'Y', 'Z': 'Z', 'x': 'X', 'y': 'Y', 'z': 'Z'}
Mapping from axis name to axis USD token
>>> import omni.isaac.core.utils.constants as constants_utils >>> >>> # get the x-axis USD token >>> constants_utils.AXES_TOKEN['x'] X >>> constants_utils.AXES_TOKEN['X'] X
Distance Metrics Utils
- rotational_distance_angle(r1: Union[numpy.ndarray, pxr.Gf.Matrix3d, pxr.Gf.Matrix4d], r2: Union[numpy.ndarray, pxr.Gf.Matrix3d, pxr.Gf.Matrix4d]) numpy.ndarray
Computes the weighted distance between two rotations using inner product.
Note
If r1 and r2 are GfMatrix3d() objects, the transformation matrices will be transposed in the distance calculations.
- Parameters
r1 (Union[np.ndarray, Gf.Matrix3d, Gf.Matrix4d]) – rotation matrices or 4x4 transformation matrices
r2 (Union[np.ndarray, Gf.Matrix3d, Gf.Matrix4d]) – rotation matrices or 4x4 transformation matrices
- Returns
the magnitude of the angle of rotation from r1 to r2
- Return type
np.ndarray
- rotational_distance_identity_matrix_deviation(r1: Union[numpy.ndarray, pxr.Gf.Matrix4d, pxr.Gf.Matrix3d], r2: Union[numpy.ndarray, pxr.Gf.Matrix4d, pxr.Gf.Matrix3d]) numpy.ndarray
Computes the distance between two rotations using deviation from identity matrix.
Note
If r1 and r2 are GfMatrix3d() objects, the transformation matrices will be transposed in the distance calculations.
- Parameters
r1 (Union[np.ndarray, Gf.Matrix4d, Gf.Matrix3d]) – rotation matrices or 4x4 transformation matrices
r2 (Union[np.ndarray, Gf.Matrix4d, Gf.Matrix3d]) – rotation matrices or 4x4 transformation matrices
- Returns
the Frobenius norm |I-r1*r2^T|, where I is the identity matrix
- Return type
np.ndarray
- rotational_distance_single_axis(r1: Union[numpy.ndarray, pxr.Gf.Matrix4d, pxr.Gf.Matrix3d], r2: Union[numpy.ndarray, pxr.Gf.Matrix4d, pxr.Gf.Matrix3d], axis: numpy.ndarray) numpy.ndarray
Computes the distance between two rotations w.r.t. input axis.
Note
If r1 and r2 are GfMatrix3d() objects, the transformation matrices will be transposed in the distance calculations.
- Usage:
If the robot were holding a cup aligned with its z-axis, it would be important to align the z-axis of the robot with the z-axis of the world frame. This could be accomplished by letting
-r1 be the rotation of the robot end effector-r2 be any rotation matrix for a rotation about the z axis-axis = [0,0,1]
- Parameters
r1 (Union[np.ndarray, Gf.Matrix4d, Gf.Matrix3d]) – rotation matrices or 4x4 transformation matrices
r2 (Union[np.ndarray, Gf.Matrix4d, Gf.Matrix3d]) – rotation matrices or 4x4 transformation matrices
axis (np.ndarray) – a 3d vector that will be rotated by r1 and r2
- Returns
the angle between (r1 @ axis) and (r2 @ axis)
- Return type
np.ndarray
- weighted_translational_distance(t1: Union[numpy.ndarray, pxr.Gf.Matrix4d], t2: Union[numpy.ndarray, pxr.Gf.Matrix4d], weight_matrix: numpy.ndarray = array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]])) numpy.ndarray
Computes the weighted distance between two translation vectors.
The distance calculation has the form sqrt(x.T W x), where
- x is the vector difference between t1 and t2.- W is a weight matrix.Given the identity weight matrix, this is equivalent to the |t1-t2|.
- Usage:
This formulation can be used to weight an arbitrary axis of the translation difference. Letting x = t1-t2 = a1*b1 + a2*b2 + a3*b3 (where b1,b2,b3 are column basis vectors, and a1,a2,a3 are constants), When W = I: x.T W x = sqrt(a1^2 + a2^2 + a3^2). To weight the b1 axis by 2, let W take the form (R.T @ ([4,1,1]@I) @ R) where:
- I is the identity matrix.- R is a rotation matrix of the form [b1,b2,b3].TThis is effectively equivalent to |[2*e1,e2,e3] @ [b1,b2,b3].T @ x| = sqrt(4*a1^2 + a2^2 + a3^2).
- e1,e2,e3 are the elementary basis vectors.
- Parameters
t1 (Union[np.ndarray, Gf.Matrix4d]) – 3d translation vectors or 4x4 transformation matrices
t2 (Union[np.ndarray, Gf.Matrix4d]) – 3d translation vectors or 4x4 transformation matrices
weight_matrix (np.ndarray, optional) – a 3x3 positive semidefinite matrix of weights. Defaults to np.eye(3).
- Returns
the weighted norm of the difference (t1-t2)
- Return type
np.ndarray
Extensions Utils
Utilities for enabling and disabling extensions from the Extension Manager and knowing their locations
- disable_extension(extension_name: str) bool
Unload an extension.
- Parameters
extension_name (str) – name of the extension
- Returns
True if extension could be unloaded, False otherwise
- Return type
bool
Example:
>>> import omni.isaac.core.utils.extensions as extensions_utils >>> >>> extensions_utils.disable_extension("omni.kit.window.stage") True
- enable_extension(extension_name: str) bool
Load an extension from the extension manager.
- Parameters
extension_name (str) – name of the extension
- Returns
True if extension could be loaded, False otherwise
- Return type
bool
Example:
>>> import omni.isaac.core.utils.extensions as extensions_utils >>> >>> extensions_utils.enable_extension("omni.kit.window.stage") True
- get_extension_id(extension_name: str) str
Get extension id for a loaded extension
- Parameters
extension_name (str) – name of the extension
- Returns
Full extension id
- Return type
str
Example:
>>> import omni.isaac.core.utils.extensions as extensions_utils >>> >>> extensions_utils.get_extension_id("omni.kit.window.stage") omni.kit.window.stage-2.4.3
- get_extension_path(ext_id: str) str
Get extension path for a loaded extension by its full id
- Parameters
ext_id (str) – full id of extension
- Returns
Path to loaded extension root directory
- Return type
str
Example:
>>> import omni.isaac.core.utils.extensions as extensions_utils >>> >>> ext_id = extensions_utils.get_extension_id("omni.kit.window.stage") >>> extensions_utils.get_extension_path(ext_id) /home/user/.local/share/ov/pkg/isaac_sim-<version>/kit/exts/omni.kit.window.stage
- get_extension_path_from_name(extension_name: str) str
Get extension path for a loaded extension by its name
- Parameters
extension_name (str) – name of the extension
- Returns
Path to loaded extension root directory
- Return type
str
Example:
>>> import omni.isaac.core.utils.extensions as extensions_utils >>> >>> extensions_utils.get_extension_path_from_name("omni.kit.window.stage") /home/user/.local/share/ov/pkg/isaac_sim-<version>/kit/exts/omni.kit.window.stage
Interoperability Utils
Utilities for interoperability between different (ML) frameworks.
Supported frameworks are:
- jax2numpy(array: jax.Array) numpy.ndarray
Convert JAX array to NumPy array
- Parameters
array (jax.Array) – JAX array
- Returns
NumPy array
- Return type
numpy.ndarray
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import jax >>> import jax.numpy as jnp >>> >>> with jax.default_device(jax.devices("cuda")[0]): ... jax_array = jnp.zeros((100, 10), dtype=jnp.float32) ... >>> numpy_array = interops_utils.jax2numpy(jax_array) >>> type(numpy_array) <class 'numpy.ndarray'>
- jax2tensorflow(array: jax.Array) tensorflow.Tensor
Convert JAX array to TensorFlow tensor
- Parameters
array (jax.Array) – JAX array
- Returns
TensorFlow tensor
- Return type
tensorflow.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import jax >>> import jax.numpy as jnp >>> >>> with jax.default_device(jax.devices("cuda")[0]): ... jax_array = jnp.zeros((100, 10), dtype=jnp.float32) ... >>> tensorflow_tensor = interops_utils.jax2tensorflow(jax_array) >>> type(tensorflow_tensor) <class 'tensorflow.python...Tensor'>
- jax2torch(array: jax.Array) torch.Tensor
Convert JAX array to PyTorch tensor
- Parameters
array (jax.Array) – JAX array
- Returns
PyTorch tensor
- Return type
torch.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import jax >>> import jax.numpy as jnp >>> >>> with jax.default_device(jax.devices("cuda")[0]): ... jax_array = jnp.zeros((100, 10), dtype=jnp.float32) ... >>> torch_tensor = interops_utils.jax2torch(jax_array) >>> type(torch_tensor) <class 'torch.Tensor'>
- jax2warp(array: jax.Array) warp.array
Convert JAX array to Warp array
- Parameters
array (jax.Array) – JAX array
- Returns
Warp array
- Return type
warp.array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import jax >>> import jax.numpy as jnp >>> >>> with jax.default_device(jax.devices("cuda")[0]): ... jax_array = jnp.zeros((100, 10), dtype=jnp.float32) ... >>> warp_array = interops_utils.jax2warp(jax_array) >>> type(warp_array) <class 'warp.types.array'>
- numpy2jax(array: numpy.ndarray) jax.Array
Convert NumPy array to JAX array
- Parameters
array (numpy.ndarray) – NumPy array
- Returns
JAX array
- Return type
jax.Array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import numpy as np >>> >>> numpy_array = np.zeros((100, 10), dtype=np.float32) >>> jax_array = interops_utils.numpy2jax(numpy_array) >>> type(jax_array) <class 'jaxlib.xla_extension.ArrayImpl'>
- numpy2tensorflow(array: numpy.ndarray) tensorflow.Tensor
Convert NumPy array to TensorFlow tensor
- Parameters
array (numpy.ndarray) – NumPy array
- Returns
TensorFlow tensor
- Return type
tensorflow.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import numpy as np >>> >>> numpy_array = np.zeros((100, 10), dtype=np.float32) >>> tensorflow_tensor = interops_utils.numpy2tensorflow(numpy_array) >>> type(tensorflow_tensor) <class 'tensorflow.python...Tensor'>
- numpy2torch(array: numpy.ndarray) torch.Tensor
Convert NumPy array to PyTorch tensor
- Parameters
array (numpy.ndarray) – NumPy array
- Returns
PyTorch tensor
- Return type
torch.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import numpy as np >>> >>> numpy_array = np.zeros((100, 10), dtype=np.float32) >>> torch_tensor = interops_utils.numpy2torch(numpy_array) >>> type(torch_tensor) <class 'torch.Tensor'>
- numpy2warp(array: numpy.ndarray) warp.array
Convert NumPy array to Warp array
- Parameters
array (numpy.ndarray) – NumPy array
- Returns
Warp array
- Return type
warp.array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import numpy as np >>> >>> numpy_array = np.zeros((100, 10), dtype=np.float32) >>> warp_array = interops_utils.numpy2warp(numpy_array) >>> type(warp_array) <class 'warp.types.array'>
- tensorflow2jax(tensor: tensorflow.Tensor) jax.Array
Convert TensorFlow tensor to JAX array
- Parameters
tensor (tensorflow.Tensor) – TensorFlow tensor
- Returns
JAX array
- Return type
jax.Array
Warning
It is expected that the conversion of
int32
TensorFlow tensors to other backends will be on the CPU, regardless of which context device is specified (see TensorFlow issues #34071, #41307, #46833)Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import tensorflow as tf >>> >>> with tf.device("/GPU:0"): ... tensorflow_tensor = tf.zeros((100, 10), dtype=tf.float32) ... >>> jax_array = interops_utils.tensorflow2jax(tensorflow_tensor) >>> type(jax_array) <class 'jaxlib.xla_extension.Array...'>
- tensorflow2numpy(tensor: tensorflow.Tensor) numpy.ndarray
Convert TensorFlow tensor to NumPy array
- Parameters
tensor (tensorflow.Tensor) – TensorFlow tensor
- Returns
NumPy array
- Return type
numpy.ndarray
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import tensorflow as tf >>> >>> with tf.device("/GPU:0"): ... tensorflow_tensor = tf.zeros((100, 10), dtype=tf.float32) ... >>> numpy_array = interops_utils.tensorflow2numpy(tensorflow_tensor) >>> type(numpy_array) <class 'numpy.ndarray'>
- tensorflow2torch(tensor: tensorflow.Tensor) torch.Tensor
Convert TensorFlow tensor to PyTorch tensor
- Parameters
tensor (tensorflow.Tensor) – TensorFlow tensor
- Returns
PyTorch tensor
- Return type
torch.Tensor
Warning
It is expected that the conversion of
int32
TensorFlow tensors to other backends will be on the CPU, regardless of which context device is specified (see TensorFlow issues #34071, #41307, #46833)Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import tensorflow as tf >>> >>> with tf.device("/GPU:0"): ... tensorflow_tensor = tf.zeros((100, 10), dtype=tf.float32) ... >>> torch_tensor = interops_utils.tensorflow2torch(tensorflow_tensor) >>> type(torch_tensor) <class 'torch.Tensor'>
- tensorflow2warp(tensor: tensorflow.Tensor) warp.array
Convert TensorFlow tensor to Warp array
- Parameters
tensor (tensorflow.Tensor) – TensorFlow tensor
- Returns
Warp array
- Return type
warp.array
Warning
It is expected that the conversion of
int32
TensorFlow tensors to other backends will be on the CPU, regardless of which context device is specified (see TensorFlow issues #34071, #41307, #46833)Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import tensorflow as tf >>> >>> with tf.device("/GPU:0"): ... tensorflow_tensor = tf.zeros((100, 10), dtype=tf.float32) ... >>> warp_array = interops_utils.tensorflow2warp(tensorflow_tensor) >>> type(warp_array) <class 'warp.types.array'>
- torch2jax(tensor: torch.Tensor) jax.Array
Convert PyTorch tensor to JAX array
- Parameters
tensor (torch.Tensor) – PyTorch tensor
- Returns
JAX array
- Return type
jax.Array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import torch >>> >>> torch_tensor = torch.zeros((100, 10), dtype=torch.float32, device=torch.device("cuda:0")) >>> jax_array = interops_utils.torch2jax(torch_tensor) >>> type(jax_array) <class 'jaxlib.xla_extension.Array...'>
- torch2numpy(tensor: torch.Tensor) numpy.ndarray
Convert PyTorch tensor to NumPy array
- Parameters
tensor (torch.Tensor) – PyTorch tensor
- Returns
NumPy array
- Return type
numpy.ndarray
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import torch >>> >>> torch_tensor = torch.zeros((100, 10), dtype=torch.float32, device=torch.device("cuda:0")) >>> numpy_array = interops_utils.torch2numpy(torch_tensor) >>> print(type(numpy_array)) <class 'numpy.ndarray'>
- torch2tensorflow(tensor: torch.Tensor) tensorflow.Tensor
Convert PyTorch tensor to TensorFlow tensor
- Parameters
tensor (torch.Tensor) – PyTorch tensor
- Returns
TensorFlow tensor
- Return type
tensorflow.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import torch >>> >>> torch_tensor = torch.zeros((100, 10), dtype=torch.float32, device=torch.device("cuda:0")) >>> tensorflow_tensor = interops_utils.torch2tensorflow(torch_tensor) >>> type(tensorflow_tensor) <class 'tensorflow.python...Tensor'>
- torch2warp(tensor: torch.Tensor) warp.array
Convert PyTorch tensor to Warp array
- Parameters
tensor (torch.Tensor) – PyTorch tensor
- Returns
Warp array
- Return type
warp.array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import torch >>> >>> torch_tensor = torch.zeros((100, 10), dtype=torch.float32, device=torch.device("cuda:0")) >>> warp_array = interops_utils.torch2warp(torch_tensor) >>> type(warp_array) <class 'warp.types.array'>
- warp2jax(array: warp.array) jax.Array
Convert Warp array to JAX array
- Parameters
array (warp.array) – Warp array
- Returns
JAX array
- Return type
jax.Array
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import warp as wp >>> >>> wp.init() >>> warp_array = wp.zeros((100, 10), dtype=wp.float32, device="cuda:0") >>> jax_array = interops_utils.warp2jax(warp_array) >>> type(jax_array) <class 'jaxlib.xla_extension.Array...'>
- warp2numpy(array: warp.array) numpy.ndarray
Convert Warp array to NumPy array
- Parameters
array (warp.array) – Warp array
- Returns
NumPy array
- Return type
numpy.ndarray
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import warp as wp >>> >>> wp.init() >>> warp_array = wp.zeros((100, 10), dtype=wp.float32, device="cuda:0") >>> numpy_array = interops_utils.warp2numpy(warp_array) >>> type(numpy_array) <class 'numpy.ndarray'>
- warp2tensorflow(array: warp.array) tensorflow.Tensor
Convert Warp array to TensorFlow tensor
- Parameters
array (warp.array) – Warp array
- Returns
TensorFlow tensor
- Return type
tensorflow.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import warp as wp >>> >>> wp.init() >>> warp_array = wp.zeros((100, 10), dtype=wp.float32, device="cuda:0") >>> tensorflow_tensor = interops_utils.warp2tensorflow(warp_array) >>> type(tensorflow_tensor) <class 'tensorflow.python...Tensor'>
- warp2torch(array: warp.array) torch.Tensor
Convert Warp array to PyTorch tensor
- Parameters
array (warp.array) – Warp array
- Returns
PyTorch tensor
- Return type
torch.Tensor
Example:
>>> import omni.isaac.core.utils.interops as interops_utils >>> import warp as wp >>> >>> wp.init() >>> warp_array = wp.zeros((100, 10), dtype=wp.float32, device="cuda:0") >>> torch_tensor = interops_utils.warp2torch(warp_array) >>> type(torch_tensor) <class 'torch.Tensor'>
Math Utils
- cross(a: Union[numpy.ndarray, list], b: Union[numpy.ndarray, list]) list
Computes the cross-product between two 3-dimensional vectors.
- Parameters
a (np.ndarray, list) – A 3-dimensional vector
b (np.ndarray, list) – A 3-dimensional vector
- Returns
Cross product between input vectors.
- Return type
np.ndarray
- normalize(v)
Normalizes the vector inline (and also returns it).
- normalized(v)
Returns a normalized copy of the provided vector.
- radians_to_degrees(rad_angles: numpy.ndarray) numpy.ndarray
Converts input angles from radians to degrees.
- Parameters
rad_angles (np.ndarray) – Input array of angles (in radians).
- Returns
Array of angles in degrees.
- Return type
np.ndarray
Mesh Utils
- get_mesh_vertices_relative_to(mesh_prim: pxr.UsdGeom.Mesh, coord_prim: pxr.Usd.Prim) numpy.ndarray
Get vertices of the mesh prim in the coordinate system of the given prim.
- Parameters
mesh_prim (UsdGeom.Mesh) – mesh prim to get the vertice points.
coord_prim (Usd.Prim) – prim used as relative coordinate.
- Returns
vertices of the mesh in the coordinate system of the given prim. Shape is (N, 3).
- Return type
np.ndarray
Example:
>>> import omni.isaac.core.utils.mesh as mesh_utils >>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # 1 stage unit length cube centered at (0.0, 0.0, 0.0) >>> mesh_prim = stage_utils.get_current_stage().GetPrimAtPath("/World/Cube") >>> # 1 stage unit diameter sphere centered at (1.0, 1.0, 1.0) >>> coord_prim = stage_utils.get_current_stage().GetPrimAtPath("/World/Sphere") >>> >>> mesh_utils.get_mesh_vertices_relative_to(mesh_prim, coord_prim) [[-1.5 -1.5 -0.5] [-0.5 -1.5 -0.5] [-1.5 -0.5 -0.5] [-0.5 -0.5 -0.5] [-1.5 -1.5 -1.5] [-0.5 -1.5 -1.5] [-1.5 -0.5 -1.5] [-0.5 -0.5 -1.5]]
Physics Utils
- get_rigid_body_enabled(prim_path: str) Optional[bool]
Get the
physics:rigidBodyEnabled
attribute from the USD Prim at the given path- Parameters
prim_path (str) – The path to the USD Prim
- Returns
The value of
physics:rigidBodyEnabled
attribute if it exists, and None if it does not exist.- Return type
Any
Example:
>>> import omni.isaac.core.utils.physics as physics_utils >>> >>> # prim without the Physics' Rigid Body property >>> physics_utils.get_rigid_body_enabled("/World/Cube") None >>> # prim with the physics Rigid Body property added and enabled >>> physics_utils.get_rigid_body_enabled("/World/Cube") True
- set_rigid_body_enabled(_value, prim_path)
If it exists, set the
physics:rigidBodyEnabled
attribute on the USD Prim at the given pathNote
If the prim does not have the physics Rigid Body property added, calling this function will have no effect
- Parameters
_value (Any) – Value to set
physics:rigidBodyEnabled
attribute toprim_path (str) – The path to the USD Prim
Example:
>>> import omni.isaac.core.utils.physics as physics_utils >>> >>> physics_utils.set_rigid_body_enabled(False, "/World/Cube")
- async simulate_async(seconds: float, steps_per_sec: int = 60, callback: Optional[Callable] = None) None
Helper function to simulate async for
seconds * steps_per_sec frames
.- Parameters
seconds (float) – time in seconds to simulate for
steps_per_sec (int, optional) – steps per second. Defaults to 60.
callback (Callable, optional) – optional function to run every step. Defaults to None.
Example:
>>> import asyncio >>> import omni.isaac.core.utils.physics as physics_utils >>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... # simulate 1 second with 120 steps per second ... await physics_utils.simulate_async(1, steps_per_sec=120) ... >>> run_coroutine(task())
>>> import asyncio >>> import omni.isaac.core.utils.physics as physics_utils >>> from omni.kit.async_engine import run_coroutine >>> >>> def callback(*args, **kwargs): ... print("callback:", args, kwargs) ... >>> async def task(): ... # simulate 1 second with 120 steps per second and call the callback on each step ... await physics_utils.simulate_async(1, 120, callback) ... >>> run_coroutine(task())
Prims Utils
- create_prim(prim_path: str, prim_type: str = 'Xform', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, usd_path: Optional[str] = None, semantic_label: Optional[str] = None, semantic_type: str = 'class', attributes: Optional[dict] = None) pxr.Usd.Prim
Create a prim into current USD stage.
The method applies specified transforms, the semantic label and set specified attributes.
- Parameters
prim_path (str) – The path of the new prim.
prim_type (str) – Prim type name
position (Sequence[float], optional) – prim position (applied last)
translation (Sequence[float], optional) – prim translation (applied last)
orientation (Sequence[float], optional) – prim rotation as quaternion
scale (np.ndarray (3), optional) – scaling factor in x, y, z.
usd_path (str, optional) – Path to the USD that this prim will reference.
semantic_label (str, optional) – Semantic label.
semantic_type (str, optional) – set to “class” unless otherwise specified.
attributes (dict, optional) – Key-value pairs of prim attributes to set.
- Raises
Exception – If there is already a prim at the prim_path
- Returns
The created USD prim.
- Return type
Usd.Prim
Example:
>>> import numpy as np >>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # create a cube (/World/Cube) of size 2 centered at (1.0, 0.5, 0.0) >>> prims_utils.create_prim( ... prim_path="/World/Cube", ... prim_type="Cube", ... position=np.array([1.0, 0.5, 0.0]), ... attributes={"size": 2.0} ... ) Usd.Prim(</World/Cube>)
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # load an USD file (franka.usd) to the stage under the path /World/panda >>> prims_utils.create_prim( ... prim_path="/World/panda", ... prim_type="Xform", ... usd_path="/home/<user>/Documents/Assets/Robots/Franka/franka.usd" ... ) Usd.Prim(</World/panda>)
- define_prim(prim_path: str, prim_type: str = 'Xform', fabric: bool = False) pxr.Usd.Prim
Create a USD Prim at the given prim_path of type prim_type unless one already exists
Note
This method will create a prim of the specified type in the specified path. To apply a transformation (position, orientation, scale), set attributes or load an USD file while creating the prim use the
create_prim
function.- Parameters
prim_path (str) – path of the prim in the stage
prim_type (str, optional) – The type of the prim to create. Defaults to “Xform”.
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Raises
Exception – If there is already a prim at the prim_path
- Returns
The created USD prim.
- Return type
Usd.Prim
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.define_prim("/World/Shapes", prim_type="Xform") Usd.Prim(</World/Shapes>)
- delete_prim(prim_path: str) None
Remove the USD Prim and its descendants from the scene if able
- Parameters
prim_path (str) – path of the prim in the stage
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.delete_prim("/World/Cube")
- find_matching_prim_paths(prim_path_regex: str, prim_type: Optional[str] = None) List[str]
Find all the matching prim paths in the stage based on Regex expression.
- Parameters
prim_path_regex (str) – The Regex expression for prim path.
prim_type (Optional[str]) – The type of the prims to filter, only supports articulation and rigid_body currently. Defaults to None.
- Returns
List of prim paths that match input expression.
- Return type
List[str]
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/env/Cube, /World/env_01/Cube, /World/env_02/Cube >>> # get only the prim Cube paths from env_01 and env_02 >>> prims_utils.find_matching_prim_paths("/World/env_.*/Cube") ['/World/env_01/Cube', '/World/env_02/Cube']
- get_all_matching_child_prims(prim_path: str, predicate: typing.Callable[[str], bool] = <function <lambda>>, depth: typing.Optional[int] = None) List[pxr.Usd.Prim]
Performs a breadth-first search starting from the root and returns all the prims matching the predicate.
- Parameters
prim_path (str) – root prim path to start traversal from.
predicate (Callable[[str], bool]) – predicate that checks the prim path of a prim and returns a boolean.
depth (Optional[int]) – maximum depth for traversal, should be bigger than zero if specified. Defaults to None (i.e: traversal till the end of the tree).
- Returns
A list containing the root and children prims matching specified predicate.
- Return type
List[Usd.Prim]
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # get all hidden prims >>> predicate = lambda path: prims_utils.is_prim_hidden_in_stage(path) # True if the prim at path is hidden >>> prims_utils.get_all_matching_child_prims("/", predicate) [Usd.Prim(</OmniverseKit_Persp>), Usd.Prim(</OmniverseKit_Front>), Usd.Prim(</OmniverseKit_Top>), Usd.Prim(</OmniverseKit_Right>), Usd.Prim(</Render>)]
- get_articulation_root_api_prim_path(prim_path)
Get the prim path that has the Articulation Root API
Note
This function assumes that all prims defined by a regular expression correspond to the same articulation type
- Parameters
prim_path (str) – path or regex of the prim(s) on which to search for the prim containing the API
- Returns
- path or regex of the prim(s) that has the Articulation Root API.
If no prim has been found, the same input value is returned
- Return type
str
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/env/Ant, /World/env_01/Ant, /World/env_02/Ant >>> # search specifying the prim with the Articulation Root API >>> prims_utils.get_articulation_root_api_prim_path("/World/env/Ant/torso") /World/env/Ant/torso >>> # search specifying some ancestor prim that does not have the Articulation Root API >>> prims_utils.get_articulation_root_api_prim_path("/World/env/Ant") /World/env/Ant/torso >>> # regular expression search >>> prims_utils.get_articulation_root_api_prim_path("/World/env.*/Ant") /World/env.*/Ant/torso
- get_first_matching_child_prim(prim_path: str, predicate: Callable[[str], bool], fabric: bool = False) pxr.Usd.Prim
Recursively get the first USD Prim at the path string that passes the predicate function
- Parameters
prim_path (str) – path of the prim in the stage
predicate (Callable[[str], bool]) – Function to test the prims against
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Returns
The first prim or child of the prim, as defined by GetChildren, that passes the predicate
- Return type
Usd.Prim
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Get the first child prim of type Cube >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Cube" >>> prims_utils.get_first_matching_child_prim("/", predicate) Usd.Prim(</World/Cube>)
- get_first_matching_parent_prim(prim_path: str, predicate: Callable[[str], bool]) pxr.Usd.Prim
Recursively get the first USD Prim at the parent path string that passes the predicate function
- Parameters
prim_path (str) – path of the prim in the stage
predicate (Callable[[str], bool]) – Function to test the prims against
- Returns
The first prim on the parent path, as defined by GetParent, that passes the predicate
- Return type
str
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Get the first parent of Cube prim of type Xform >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Xform" >>> prims_utils.get_first_matching_parent_prim("/World/Cube", predicate) Usd.Prim(</World>)
- get_prim_at_path(prim_path: str, fabric: bool = False) Union[pxr.Usd.Prim, usdrt.Usd._Usd.Prim]
Get the USD or Fabric Prim at a given path string
- Parameters
prim_path (str) – path of the prim in the stage.
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Returns
USD or Fabric Prim object at the given path in the current stage.
- Return type
Union[Usd.Prim, usdrt.Usd._Usd.Prim]
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_at_path("/World/Cube") Usd.Prim(</World/Cube>)
- get_prim_attribute_names(prim_path: str, fabric: bool = False) List[str]
Get all the attribute names of a prim at the path
- Parameters
prim_path (str) – path of the prim in the stage
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Raises
Exception – If there is not a valid prim at the given path
- Returns
List of the prim attribute names
- Return type
List[str]
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_attribute_names("/World/Cube") ['doubleSided', 'extent', 'orientation', 'primvars:displayColor', 'primvars:displayOpacity', 'purpose', 'size', 'visibility', 'xformOp:orient', 'xformOp:scale', 'xformOp:translate', 'xformOpOrder']
- get_prim_attribute_value(prim_path: str, attribute_name: str, fabric: bool = False) Any
Get a prim attribute value
- Parameters
prim_path (str) – path of the prim in the stage
attribute_name (str) – name of the attribute to get
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Raises
Exception – If there is not a valid prim at the given path
- Returns
Prim attribute value
- Return type
Any
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_attribute_value("/World/Cube", attribute_name="size") 1.0
- get_prim_children(prim: pxr.Usd.Prim) List[pxr.Usd.Prim]
Return the call of the USD Prim’s GetChildren member function
- Parameters
prim (Usd.Prim) – The parent USD Prim
- Returns
A list of the prim’s children.
- Return type
List[Usd.Prim]
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Get all prims under the prim World >>> prim = prims_utils.get_prim_at_path("/World") >>> prims_utils.get_prim_children(prim) [Usd.Prim(</World/Cube>), Usd.Prim(</World/Cube_01>), Usd.Prim(</World/Cube_02>)]
- get_prim_object_type(prim_path: str) Optional[str]
Get the dynamic control object type of the USD Prim at the given path.
If the prim at the path is of Dynamic Control type e.g.: rigid_body, joint, dof, articulation, attractor, d6joint, then the corresponding string returned. If is an Xformable prim, then “xform” is returned. Otherwise None is returned.
- Parameters
prim_path (str) – path of the prim in the stage
- Raises
Exception – If the USD Prim is not a supported type.
- Returns
String corresponding to the object type.
- Return type
str
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_object_type("/World/Cube") xform
- get_prim_parent(prim: pxr.Usd.Prim) pxr.Usd.Prim
Return the call of the USD Prim’s GetChildren member function
- Parameters
prim (Usd.Prim) – The USD Prim to call GetParent on
- Returns
The prim’s parent returned from GetParent
- Return type
Usd.Prim
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Get the prim Cube's parent >>> prim = prims_utils.get_prim_at_path("/World/Cube") >>> prims_utils.get_prim_parent(prim) Usd.Prim(</World>)
- get_prim_path(prim: pxr.Usd.Prim) str
Get the path of a given USD prim.
- Parameters
prim (Usd.Prim) – The input USD prim.
- Returns
The path to the input prim.
- Return type
str
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prim = prims_utils.get_prim_at_path("/World/Cube") # Usd.Prim(</World/Cube>) >>> prims_utils.get_prim_path(prim) /World/Cube
- get_prim_property(prim_path: str, property_name: str) Any
Get the attribute of the USD Prim at the given path
- Parameters
prim_path (str) – path of the prim in the stage
property_name (str) – name of the attribute to get
- Returns
The attribute if it exists, None otherwise
- Return type
Any
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_property("/World/Cube", property_name="size") 1.0
- get_prim_type_name(prim_path: str, fabric: bool = False) str
Get the TypeName of the USD Prim at the path if it is valid
- Parameters
prim_path (str) – path of the prim in the stage
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Raises
Exception – If there is not a valid prim at the given path
- Returns
The TypeName of the USD Prim at the path string
- Return type
str
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prims_utils.get_prim_type_name("/World/Cube") Cube
- is_prim_ancestral(prim_path: str) bool
Check if any of the prims ancestors were brought in as a reference
- Parameters
prim_path (str) – The path to the USD prim.
- Returns
True if prim is part of a referenced prim, false otherwise.
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # /World/Cube is a prim created >>> prims_utils.is_prim_ancestral("/World/Cube") False >>> # /World/panda is an USD file loaded (as reference) under that path >>> prims_utils.is_prim_ancestral("/World/panda") False >>> prims_utils.is_prim_ancestral("/World/panda/panda_link0") True
Checks if the prim is hidden in the USd stage or not.
Warning
This function checks for the
hide_in_stage_window
prim metadata. This metadata is not related to the visibility of the prim.- Parameters
prim_path (str) – The path to the USD prim.
- Returns
True if prim is hidden from stage window, False if not hidden.
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # prim without the 'hide_in_stage_window' metadata >>> prims_utils.is_prim_hidden_in_stage("/World/Cube") None >>> # prim with the 'hide_in_stage_window' metadata set to True >>> prims_utils.is_prim_hidden_in_stage("/World/Cube") True
- is_prim_no_delete(prim_path: str) bool
Checks whether a prim can be deleted or not from USD stage.
Note
This function checks for the
no_delete
prim metadata. A prim with this metadata set to True cannot be deleted by using the edit menu, the context menu, or by calling thedelete_prim
function, for example.- Parameters
prim_path (str) – The path to the USD prim.
- Returns
True if prim cannot be deleted, False if it can
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # prim without the 'no_delete' metadata >>> prims_utils.is_prim_no_delete("/World/Cube") None >>> # prim with the 'no_delete' metadata set to True >>> prims_utils.is_prim_no_delete("/World/Cube") True
- is_prim_non_root_articulation_link(prim_path: str) bool
Used to query if the prim_path corresponds to a link in an articulation which is a non root link.
- Parameters
prim_path (str) – prim_path to query
- Returns
- True if the prim path corresponds to a link in an articulation which is a non root link
and can’t have a transformation applied to it.
- Return type
bool
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # /World/panda contains the prim tree for the Franka panda robot. >>> # The prim on this path has the Physics Articulation Root property applied >>> prims_utils.is_prim_non_root_articulation_link("/World/panda") False >>> prims_utils.is_prim_non_root_articulation_link("/World/panda/panda_link0") True
- is_prim_path_valid(prim_path: str, fabric: bool = False) bool
Check if a path has a valid USD Prim at it
- Parameters
prim_path (str) – path of the prim in the stage
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
- Returns
True if the path points to a valid prim
- Return type
bool
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube >>> prims_utils.is_prim_path_valid("/World/Cube") True >>> prims_utils.is_prim_path_valid("/World/Cube/") False >>> prims_utils.is_prim_path_valid("/World/Sphere") # it doesn't exist False
- is_prim_root_path(prim_path: str) bool
Checks if the input prim path is root or not.
- Parameters
prim_path (str) – The path to the USD prim.
- Returns
True if the prim path is “/”, False otherwise
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube >>> prims_utils.is_prim_root_path("/") True >>> prims_utils.is_prim_root_path("/World") False >>> prims_utils.is_prim_root_path("/World/Cube") False
- move_prim(path_from: str, path_to: str) None
Run the Move command to change a prims USD Path in the stage
- Parameters
path_from (str) – Path of the USD Prim you wish to move
path_to (str) – Final destination of the prim
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Move the prim Cube outside the prim World >>> prims_utils.move_prim("/World/Cube", "/Cube")
- query_parent_path(prim_path: str, predicate: Callable[[str], bool]) bool
Check if one of the ancestors of the prim at the prim_path can pass the predicate
- Parameters
prim_path (str) – path to the USD Prim for which to check the ancestors
predicate (Callable[[str], bool]) – The condition that must be True about the ancestors
- Returns
True if there is an ancestor that can pass the predicate, False otherwise
- Return type
bool
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Check is the prim Cube has an ancestor of type Xform >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Xform" >>> prims_utils.query_parent_path("/World/Cube", predicate) True
- set_prim_attribute_value(prim_path: str, attribute_name: str, value: Any, fabric: bool = False)
Set a prim attribute value
- Parameters
prim_path (str) – path of the prim in the stage
attribute_name (str) – name of the attribute to set
value (Any) – value to set the attribute to
fabric (bool, optional) – True for fabric stage and False for USD stage. Defaults to False.
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Set the Cube size to 5.0 >>> prims_utils.set_prim_attribute_value("/World/Cube", attribute_name="size", value=5.0)
- set_prim_hide_in_stage_window(prim: pxr.Usd.Prim, hide: bool)
Set
hide_in_stage_window
metadata for a primWarning
This metadata is unrelated to the visibility of the prim. Use the
set_prim_visibility
function for the latter purpose- Parameters
prim (Usd.Prim) – Prim to set
hide (bool) – True to hide in stage window, false to show
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prim = prims_utils.get_prim_at_path("/World/Cube") >>> prims_utils.set_prim_hide_in_stage_window(prim, True)
- set_prim_no_delete(prim: pxr.Usd.Prim, no_delete: bool)
Set
no_delete
metadata for a primNote
A prim with this metadata set to True cannot be deleted by using the edit menu, the context menu, or by calling the
delete_prim
function, for example.- Parameters
prim (Usd.Prim) – Prim to set
no_delete (bool) – True to make prim undeletable in stage window, false to allow deletion
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> prim = prims_utils.get_prim_at_path("/World/Cube") >>> prims_utils.set_prim_no_delete(prim, True)
- set_prim_property(prim_path: str, property_name: str, property_value: Any) None
Set the attribute of the USD Prim at the path
- Parameters
prim_path (str) – path of the prim in the stage
property_name (str) – name of the attribute to set
property_value (Any) – value to set the attribute to
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Set the Cube size to 5.0 >>> prims_utils.set_prim_property("/World/Cube", property_name="size", property_value=5.0)
- set_prim_visibility(prim: pxr.Usd.Prim, visible: bool) None
Sets the visibility of the prim in the opened stage.
Note
The method does this through the USD API.
- Parameters
prim (Usd.Prim) – the USD prim
visible (bool) – flag to set the visibility of the usd prim in stage.
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube. Make the Cube not visible >>> prim = prims_utils.get_prim_at_path("/World/Cube") >>> prims_utils.set_prim_visibility(prim, False)
- set_targets(prim: pxr.Usd.Prim, attribute: str, target_prim_paths: list)
Set targets for a prim relationship attribute
- Parameters
prim (Usd.Prim) – Prim to create and set attribute on
attribute (str) – Relationship attribute to create
target_prim_paths (list) – list of targets to set
Example:
>>> import omni.isaac.core.utils.prims as prims_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Set each prim Cube to the relationship targetPrim of the prim World >>> prim = prims_utils.get_prim_at_path("/World") >>> targets = ["/World/Cube", "/World/Cube_01", "/World/Cube_02"] >>> prims_utils.set_targets(prim, "targetPrim", targets)
Random Utils
- get_random_translation_from_camera(min_distance: float, max_distance: float, fov_x: float, fov_y: float, fraction_to_screen_edge: float) numpy.ndarray
Get a random translation from the camera, in the camera’s frame, that’s in view of the camera.
- Parameters
min_distance (float) – minimum distance away from the camera (along the optical axis) of the random translation.
max_distance (float) – maximum distance away from the camera (along the optical axis) of the random translation.
fov_x (float) – field of view of the camera in the x-direction in radians.
fov_y (float) – field of view of the camera in the y-direction in radians.
fraction_to_screen_edge (float) – maximum allowed fraction to the edge of the screen the translated point may appear when viewed from the camera. A value of 0 corresponds to the translated point being centered in the camera’s view (on the optical axis), whereas a value of 1 corresponds to the translated point being on the edge of the screen in the camera’s view.
- Returns
- random translation from the camera, in the camera’s frame, that’s in view of the camera. Shape
is (3, ).
- Return type
np.ndarray
- get_random_values_in_range(min_range: numpy.ndarray, max_range: numpy.ndarray) numpy.ndarray
Get an array of random values where each element is between the corresponding min_range and max_range element.
- Parameters
min_range (np.ndarray) – minimum values for each corresponding element of the array of random values. Shape is (num_values, ).
max_range (np.ndarray) – maximum values for each corresponding element of the array of random values. Shape is (num_values, ).
- Returns
array of random values. Shape is (num_values, ).
- Return type
np.ndarray
- get_random_world_pose_in_view(camera_prim: pxr.Usd.Prim, min_distance: float, max_distance: float, fov_x: float, fov_y: float, fraction_to_screen_edge: float, coord_prim: pxr.Usd.Prim, min_rotation_range: numpy.ndarray, max_rotation_range: numpy.ndarray) Tuple[numpy.ndarray, numpy.ndarray]
Get a pose defined in the world frame that’s in view of the camera.
- Parameters
camera_prim (Usd.Prim) – prim path of the camera.
min_distance (float) – minimum distance away from the camera (along the optical axis) of the random translation.
max_distance (float) – maximum distance away from the camera (along the optical axis) of the random translation.
fov_x (float) – field of view of the camera in the x-direction in radians.
fov_y (float) – field of view of the camera in the y-direction in radians.
fraction_to_screen_edge (float) – maximum allowed fraction to the edge of the screen the translated point may appear when viewed from the camera. A value of 0 corresponds to the translated point being centered in the camera’s view (on the optical axis), whereas a value of 1 corresponds to the translated point being on the edge of the screen in the camera’s view.
coord_prim (Usd.Prim) – prim whose frame the orientation is defined with respect to.
min_rotation_range (np.ndarray) – minimum XYZ Euler angles of the random pose, defined with respect to the frame of the prim at coord_prim. Shape is (3, ).
max_rotation_range (np.ndarray) – maximum XYZ Euler angles of the random pose, defined with respect to the frame of the prim at coord_prim.
- Returns
- first index is position in the world frame. Shape is (3, ). Second index is
quaternion orientation in the world frame. Quaternion is scalar-first (w, x, y, z). Shape is (4, ).
- Return type
Tuple[np.ndarray, np.ndarray]
Render Product Utils
- add_aov(render_product_path: str, aov_name: str)
Adds an AOV/Render Var to an existing render product
- Parameters
render_product_path (str) – path to the render product prim
aov_name (str) – Name of the render var we want to add to this render product
- Raises
RuntimeError – If the render product path is invalid
RuntimeError – If the renderVar could not be created
RuntimeError – If the renderVar could not be added to the render product
- create_hydra_texture(resolution: Tuple[int], camera_prim_path: str)
- get_camera_prim_path(render_product_path: str)
Get the current camera for a render product
- Parameters
render_product_path (str) – path to the render product prim
- Raises
RuntimeError – If the render product path is invalid
- Returns
Path to the camera prim attached to this render product
- Return type
str
- get_resolution(render_product_path: str)
Get resolution for a render product
- Parameters
render_product_path (str) – path to the render product prim
- Raises
RuntimeError – If the render product path is invalid
- Returns
(width,height)
- Return type
Tuple[int]
- set_camera_prim_path(render_product_path: str, camera_prim_path: str)
Sets the camera prim path for a render product
- Parameters
render_product_path (str) – path to the render product prim
camera_prim_path (str) – path to the camera prim
- Raises
RuntimeError – If the render product path is invalid
- set_resolution(render_product_path: str, resolution: Tuple[int])
Set resolution for a render product
- Parameters
render_product_path (str) – path to the render product prim
resolution (Tuple[float]) – width,height for render product
- Raises
RuntimeError – If the render product path is invalid
Rotations Utils
- euler_angles_to_quat(euler_angles: numpy.ndarray, degrees: bool = False, extrinsic: bool = True) numpy.ndarray
Convert Euler angles to quaternion.
- Parameters
euler_angles (np.ndarray) – Euler XYZ angles.
degrees (bool, optional) – Whether input angles are in degrees. Defaults to False.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
quaternion (w, x, y, z).
- Return type
np.ndarray
- euler_to_rot_matrix(euler_angles: numpy.ndarray, degrees: bool = False, extrinsic: bool = True) numpy.ndarray
Convert Euler XYZ or ZYX angles to rotation matrix.
- Parameters
euler_angles (np.ndarray) – Euler angles.
degrees (bool, optional) – Whether passed angles are in degrees.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
A 3x3 rotation matrix in its extrinsic or intrinsic form depends on the extrinsic argument.
- Return type
np.ndarray
- gf_quat_to_np_array(orientation: Union[pxr.Gf.Quatd, pxr.Gf.Quatf, pxr.Gf.Quaternion]) numpy.ndarray
Converts a pxr Quaternion type to a numpy array following [w, x, y, z] convention.
- Parameters
orientation (Union[Gf.Quatd, Gf.Quatf, Gf.Quaternion]) – Input quaternion object.
- Returns
A (4,) quaternion array in (w, x, y, z).
- Return type
np.ndarray
- gf_rotation_to_np_array(orientation: pxr.Gf.Rotation) numpy.ndarray
Converts a pxr Rotation type to a numpy array following [w, x, y, z] convention.
- Parameters
orientation (Gf.Rotation) – Pxr rotation object.
- Returns
A (4,) quaternion array in (w, x, y, z).
- Return type
np.ndarray
- lookat_to_quatf(camera: pxr.Gf.Vec3f, target: pxr.Gf.Vec3f, up: pxr.Gf.Vec3f) pxr.Gf.Quatf
[summary]
- Parameters
camera (Gf.Vec3f) – [description]
target (Gf.Vec3f) – [description]
up (Gf.Vec3f) – [description]
- Returns
Pxr quaternion object.
- Return type
Gf.Quatf
- matrix_to_euler_angles(mat: numpy.ndarray, degrees: bool = False, extrinsic: bool = True) numpy.ndarray
Convert rotation matrix to Euler XYZ extrinsic or intrinsic angles.
- Parameters
mat (np.ndarray) – A 3x3 rotation matrix.
degrees (bool, optional) – Whether returned angles should be in degrees.
extrinsic (bool, optional) – True if the rotation matrix follows the extrinsic matrix convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic matrix conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
Euler XYZ angles (intrinsic form) if extrinsic is False and Euler XYZ angles (extrinsic form) if extrinsic is True.
- Return type
np.ndarray
- quat_to_euler_angles(quat: numpy.ndarray, degrees: bool = False, extrinsic: bool = True) numpy.ndarray
Convert input quaternion to Euler XYZ or ZYX angles.
- Parameters
quat (np.ndarray) – Input quaternion (w, x, y, z).
degrees (bool, optional) – Whether returned angles should be in degrees. Defaults to False.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
Euler XYZ angles (intrinsic form) if extrinsic is False and Euler XYZ angles (extrinsic form) if extrinsic is True.
- Return type
np.ndarray
- quat_to_rot_matrix(quat: numpy.ndarray) numpy.ndarray
Convert input quaternion to rotation matrix.
- Parameters
quat (np.ndarray) – Input quaternion (w, x, y, z).
- Returns
A 3x3 rotation matrix.
- Return type
np.ndarray
- rot_matrix_to_quat(mat: numpy.ndarray) numpy.ndarray
Convert rotation matrix to Quaternion.
- Parameters
mat (np.ndarray) – A 3x3 rotation matrix.
- Returns
quaternion (w, x, y, z).
- Return type
np.ndarray
Semantics Utils
- add_update_semantics(prim: pxr.Usd.Prim, semantic_label: str, type_label: str = 'class', suffix='') None
Apply a semantic label to a prim or update an existing label
- Parameters
prim (Usd.Prim) – Usd Prim to add or update semantics on
semantic_label (str) – The label we want to apply
type_label (str) – The type of semantic information we are specifying (default = “class”)
suffix (str) – Additional suffix used to specify multiple semantic attribute names.
"Semantics" (By default the semantic attribute name is) –
additional (and to specify) –
used (attributes a suffix can be provided. Simple string concatenation is) – “Semantics” + suffix (default = “”)
- check_incorrect_semantics(prim_path: Optional[str] = None) List[List[str]]
Returns a list of prim path of meshes with different semantics labels than their prim path and their semantic labels
- Parameters
prim_path (str) – This will check Prim path and its childrens’ semantics
- Returns
List of prim path and semantic label
- Return type
List[List[str]]
- check_missing_semantics(prim_path: Optional[str] = None) List[str]
Returns a list of prim path of meshes with missing semantics
- Parameters
prim_path (str) – This will check Prim path and its childrens’ semantics
- Returns
Prim paths
- Return type
List[str]
- count_semantics_in_scene(prim_path: Optional[str] = None) Dict[str, int]
Returns a dictionary of labels and the corresponding count
- Parameters
prim_path (str) – This will check Prim path and its childrens’ semantics
- Returns
labels and count
- Return type
Dict[str, int]
- get_semantics(prim: pxr.Usd.Prim) Dict[str, Tuple[str, str]]
Returns semantics that are applied to a prim
- Parameters
prim (Usd.Prim) – Prim to return semantics for
- Returns
Dictionary containing the name of the applied semantic, and the type and data associated with that semantic.
- Return type
Dict[str, Tuple[str,str]]
- remove_all_semantics(prim: pxr.Usd.Prim, recursive: bool = False) None
Removes all semantic tags from a given prim and its children
- Parameters
prim (Usd.Prim) – Prim to remove any applied semantic APIs on
recursive (bool, optional) – Also traverse children and remove semantics recursively. Defaults to False.
Stage Utils
- add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = 'Xform') pxr.Usd.Prim
Add USD reference to the opened stage at specified prim path.
- Parameters
usd_path (str) – The path to USD file.
prim_path (str) – The prim path to attach reference.
prim_type (str, optional) – The type of prim. Defaults to “Xform”.
- Raises
FileNotFoundError – When input USD file is found at specified path.
- Returns
The USD prim at specified prim path.
- Return type
Usd.Prim
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # load an USD file (franka.usd) to the stage under the path /World/panda >>> stage_utils.add_reference_to_stage( ... usd_path="/home/<user>/Documents/Assets/Robots/Franka/franka.usd", ... prim_path="/World/panda" ... ) Usd.Prim(</World/panda>)
- clear_stage(predicate: Optional[Callable[[str], bool]] = None) None
Deletes all prims in the stage without populating the undo command buffer
- Parameters
predicate (Optional[Callable[[str], bool]], optional) – user defined function that takes a prim_path (str) as input and returns True/False if the prim should/shouldn’t be deleted. If predicate is None, a default is used that deletes all prims
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # clear the whole stage >>> stage_utils.clear_stage() >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Delete only the prims of type Cube >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Cube" >>> stage_utils.clear_stage(predicate) # after the execution the stage will be /World
- close_stage(callback_fn: Optional[Callable] = None) bool
Closes the current opened USD stage.
Note
Once the stage is closed, it is necessary to open a new stage or create a new one in order to work on it.
- Parameters
callback_fn (Callable, optional) – Callback function to call while closing. Defaults to None.
- Returns
True if operation is successful, otherwise false.
- Return type
bool
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.close_stage() True
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> def callback(*args, **kwargs): ... print("callback:", args, kwargs) ... >>> stage_utils.close_stage(callback) True >>> stage_utils.close_stage(callback) callback: (False, 'Stage opening or closing already in progress!!') {} False
- create_new_stage() pxr.Usd.Stage
Create a new stage.
- Returns
The created USD stage.
- Return type
Usd.Stage
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.create_new_stage() True
- async create_new_stage_async() None
Create a new stage (asynchronous version).
Example:
>>> import asyncio >>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await stage_utils.create_new_stage_async() ... >>> run_coroutine(task())
- get_current_stage(fabric: bool = False) Union[pxr.Usd.Stage, usdrt.Usd._Usd.Stage]
Get the current open USD or Fabric stage
- Parameters
fabric (bool, optional) – True to get the fabric stage. False to get the USD stage. Defaults to False.
- Returns
The USD or Fabric stage as specified by the input arg fabric.
- Return type
Union[Usd.Stage, usdrt.Usd._Usd.Stage]
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.get_current_stage() Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x7fba6c04f840:World7.usd'), sessionLayer=Sdf.Find('anon:0x7fba6c01c5c0:World7-session.usda'), pathResolverContext=<invalid repr>)
- get_next_free_path(path: str, parent: Optional[str] = None) str
Returns the next free usd path for the current stage
- Parameters
path (str) – path we want to check
parent (str, optional) – Parent prim for the given path. Defaults to None.
- Returns
a new path that is guaranteed to not exist on the current stage
- Return type
str
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01. >>> # Get the next available path for /World/Cube >>> stage_utils.get_next_free_path("/World/Cube") /World/Cube_02
- get_stage_units() float
Get the stage meters per unit currently set
The most common units and their values are listed in the following table:
Unit
Value
kilometer (km)
1000.0
meters (m)
1.0
inch (in)
0.0254
centimeters (cm)
0.01
millimeter (mm)
0.001
- Returns
current stage meters per unit
- Return type
float
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.get_stage_units() 1.0
- get_stage_up_axis() str
Get the current up-axis of USD stage.
- Returns
The up-axis of the stage.
- Return type
str
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.get_stage_up_axis() Z
- is_stage_loading() bool
Convenience function to see if any files are being loaded.
- Returns
True if loading, False otherwise
- Return type
bool
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.is_stage_loading() False
- open_stage(usd_path: str) bool
Open the given usd file and replace currently opened stage.
- Parameters
usd_path (str) – Path to the USD file to open.
- Raises
ValueError – When input path is not a supported file type by USD.
- Returns
True if operation is successful, otherwise false.
- Return type
bool
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.open_stage("/home/<user>/Documents/Assets/Robots/Franka/franka.usd") True
- async open_stage_async(usd_path: str) Tuple[bool, int]
Open the given usd file and replace currently opened stage (asynchronous version).
- Parameters
usd_path (str) – Path to the USD file to open.
- Raises
ValueError – When input path is not a supported file type by USD.
- Returns
True if operation is successful, otherwise false.
- Return type
bool
Example:
>>> import asyncio >>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await stage_utils.open_stage_async("/home/<user>/Documents/Assets/Robots/Franka/franka.usd") ... >>> run_coroutine(task())
- print_stage_prim_paths(fabric: bool = False) None
Traverses the stage and prints all prim (hidden or not) paths.
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> stage_utils.print_stage_prim_paths() /Render /World /World/Cube /World/Cube_01 /World/Cube_02 /OmniverseKit_Persp /OmniverseKit_Front /OmniverseKit_Top /OmniverseKit_Right
- save_stage(usd_path: str, save_and_reload_in_place=True) bool
Save usd file to path, it will be overwritten with the current stage
- Parameters
usd_path (str) – File path to save the current stage to
save_and_reload_in_place (bool, optional) – use
save_as_stage
to save and reload the root layer in place. Defaults to True.
- Raises
ValueError – When input path is not a supported file type by USD.
- Returns
True if operation is successful, otherwise false.
- Return type
bool
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.save_stage("/home/<user>/Documents/Save/stage.usd") True
- set_livesync_stage(usd_path: str, enable: bool) bool
Save the stage and set the Live Sync mode for real-time live editing of shared files on a Nucleus server
- Parameters
usd_path (str) – path to enable live sync for, it will be overwritten with the current stage
enable (bool) – True to enable livesync, false to disable livesync
- Returns
True if operation is successful, otherwise false.
- Return type
bool
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.set_livesync_stage("omniverse://localhost/Users/Live/stage.usd", enable=True) server omniverse://localhost: ConnectionStatus.CONNECTING server omniverse://localhost: ConnectionStatus.CONNECTED True
- set_stage_units(stage_units_in_meters: float) None
Set the stage meters per unit
The most common units and their values are listed in the following table:
Unit
Value
kilometer (km)
1000.0
meters (m)
1.0
inch (in)
0.0254
centimeters (cm)
0.01
millimeter (mm)
0.001
- Parameters
stage_units_in_meters (float) – units for stage
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.set_stage_units(1.0)
- set_stage_up_axis(axis: str = 'z') None
Change the up axis of the current stage
- Parameters
axis (UsdGeom.Tokens, optional) – valid values are
"x"
,"y"
and"z"
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # set stage up axis to Y-up >>> stage_utils.set_stage_up_axis("y")
- traverse_stage(fabric=False) Iterable
Traverse through prims (hidden or not) in the opened Usd stage.
- Returns
Generator which yields prims from the stage in depth-first-traversal order.
- Return type
Iterable
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Traverse through prims in the stage >>> for prim in stage_utils.traverse_stage(): >>> print(prim) Usd.Prim(</World>) Usd.Prim(</World/Cube>) Usd.Prim(</World/Cube_01>) Usd.Prim(</World/Cube_02>) Usd.Prim(</OmniverseKit_Persp>) Usd.Prim(</OmniverseKit_Front>) Usd.Prim(</OmniverseKit_Top>) Usd.Prim(</OmniverseKit_Right>) Usd.Prim(</Render>)
- update_stage() None
Update the current USD stage.
Example:
>>> import omni.isaac.core.utils.stage as stage_utils >>> >>> stage_utils.update_stage()
- async update_stage_async() None
Update the current USD stage (asynchronous version).
Example:
>>> import asyncio >>> import omni.isaac.core.utils.stage as stage_utils >>> from omni.kit.async_engine import run_coroutine >>> >>> async def task(): ... await stage_utils.update_stage_async() ... >>> run_coroutine(task())
String Utils
- find_root_prim_path_from_regex(prim_path_regex: str) Tuple[str, int]
Find the first prim above the regex pattern prim and its position.
- Parameters
prim_path_regex (str) – full prim path including the regex pattern prim.
- Returns
- First position is the prim path to the parent of the regex prim.
Second position represents the level of the regex prim in the USD stage tree representation.
- Return type
Tuple[str, int]
- find_unique_string_name(initial_name: str, is_unique_fn: Callable[[str], bool]) str
Find a unique string name based on the predicate function provided.
The string is appended with “_N”, where N is a natural number till the resultant string is unique.
- Parameters
initial_name (str) – The initial string name.
is_unique_fn (Callable[[str], bool]) – The predicate function to validate against.
- Returns
A unique string based on input function.
- Return type
str
Transformations Utils
- get_relative_transform(source_prim: pxr.Usd.Prim, target_prim: pxr.Usd.Prim) numpy.ndarray
Get the relative transformation matrix from the source prim to the target prim.
- Parameters
source_prim (Usd.Prim) – source prim from which frame to compute the relative transform.
target_prim (Usd.Prim) – target prim to which frame to compute the relative transform.
- Returns
Column-major transformation matrix with shape (4, 4).
- Return type
np.ndarray
- get_transform_with_normalized_rotation(transform: numpy.ndarray) numpy.ndarray
Get the transform after normalizing rotation component.
- Parameters
transform (np.ndarray) – transformation matrix with shape (4, 4).
- Returns
transformation matrix with normalized rotation with shape (4, 4).
- Return type
np.ndarray
- get_translation_from_target(translation_from_source: numpy.ndarray, source_prim: pxr.Usd.Prim, target_prim: pxr.Usd.Prim) numpy.ndarray
Get a translation with respect to the target’s frame, from a translation in the source’s frame.
- Parameters
translation_from_source (np.ndarray) – translation from the frame of the prim at source_path. Shape is (3, ).
source_prim (Usd.Prim) – prim path of the prim whose frame the original/untransformed translation (translation_from_source) is defined with respect to.
target_prim (Usd.Prim) – prim path of the prim whose frame corresponds to the target frame that the returned translation will be defined with respect to.
- Returns
translation with respect to the target’s frame. Shape is (3, ).
- Return type
np.ndarray
- get_world_pose_from_relative(coord_prim: pxr.Usd.Prim, relative_translation: numpy.ndarray, relative_orientation: numpy.ndarray) Tuple[numpy.ndarray, numpy.ndarray]
Get a pose defined in the world frame from a pose defined relative to the frame of the coord_prim.
- Parameters
coord_prim (Usd.Prim) – path of the prim whose frame the relative pose is defined with respect to.
relative_translation (np.ndarray) – translation relative to the frame of the prim at prim_path. Shape is (3, ).
relative_orientation (np.ndarray) – quaternion orientation relative to the frame of the prim at prim_path. Quaternion is scalar-first (w, x, y, z). Shape is (4, ).
- Returns
- first index is position in the world frame. Shape is (3, ). Second index is
quaternion orientation in the world frame. Quaternion is scalar-first (w, x, y, z). Shape is (4, ).
- Return type
Tuple[np.ndarray, np.ndarray]
- pose_from_tf_matrix(transformation: numpy.ndarray) Tuple[numpy.ndarray, numpy.ndarray]
Gets pose corresponding to input transformation matrix.
- Parameters
transformation (np.ndarray) – Column-major transformation matrix. shape is (4, 4).
- Returns
- first index is translation corresponding to transformation. shape is (3, ).
second index is quaternion orientation corresponding to transformation. quaternion is scalar-first (w, x, y, z). shape is (4, ).
- Return type
Tuple[np.ndarray, np.ndarray]
- tf_matrices_from_poses(translations: Union[numpy.ndarray, torch.Tensor], orientations: Union[numpy.ndarray, torch.Tensor]) Union[numpy.ndarray, torch.Tensor]
[summary]
- Parameters
translations (Union[np.ndarray, torch.Tensor]) – translations with shape (N, 3).
orientations (Union[np.ndarray, torch.Tensor]) – quaternion representation (scalar first) with shape (N, 4).
- Returns
transformation matrices with shape (N, 4, 4)
- Return type
Union[np.ndarray, torch.Tensor]
- tf_matrix_from_pose(translation: Sequence[float], orientation: Sequence[float]) numpy.ndarray
Compute input pose to transformation matrix.
- Parameters
pos (Sequence[float]) – The translation vector.
rot (Sequence[float]) – The orientation quaternion.
- Returns
A 4x4 matrix.
- Return type
np.ndarray
Types Utils
- class ArticulationAction(joint_positions: Optional[Union[List, numpy.ndarray]] = None, joint_velocities: Optional[Union[List, numpy.ndarray]] = None, joint_efforts: Optional[Union[List, numpy.ndarray]] = None, joint_indices: Optional[Union[List, numpy.ndarray]] = None)
[summary]
- Parameters
joint_positions (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
joint_velocities (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
joint_efforts (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
- get_dict() dict
[summary]
- Returns
[description]
- Return type
dict
- get_dof_action(index: int) dict
[summary]
- Parameters
index (int) – [description]
- Returns
[description]
- Return type
dict
- get_length() Optional[int]
[summary]
- Returns
[description]
- Return type
Optional[int]
- class ArticulationActions(joint_positions: Optional[Union[List, numpy.ndarray]] = None, joint_velocities: Optional[Union[List, numpy.ndarray]] = None, joint_efforts: Optional[Union[List, numpy.ndarray]] = None, joint_indices: Optional[Union[List, numpy.ndarray]] = None)
[summary]
- Parameters
joint_positions (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
joint_velocities (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
joint_efforts (Optional[Union[List, np.ndarray]], optional) – [description]. Defaults to None.
- class DOFInfo(prim_path: str, handle: int, prim: pxr.Usd.Prim, index: int)
[summary]
- Parameters
prim_path (str) – [description]
handle (int) – [description]
prim (Usd.Prim) – [description]
index (int) – [description]
- class DataFrame(current_time_step: int, current_time: float, data: dict)
[summary]
- Parameters
current_time_step (int) – [description]
current_time (float) – [description]
data (dict) – [description]
- get_dict() dict
[summary]
- Returns
[description]
- Return type
dict
- class DynamicState(position: numpy.ndarray, orientation: numpy.ndarray, linear_velocity: numpy.ndarray, angular_velocity: numpy.ndarray)
[summary]
- Parameters
position (np.ndarray) – [description]
orientation (np.ndarray) – [description]
- class DynamicsViewState(positions: Union[numpy.ndarray, torch.Tensor], orientations: Union[numpy.ndarray, torch.Tensor], linear_velocities: Union[numpy.ndarray, torch.Tensor], angular_velocities: Union[numpy.ndarray, torch.Tensor])
[summary]
- Parameters
position (np.ndarray) – [description]
orientation (np.ndarray) – [description]
- class JointsState(positions: numpy.ndarray, velocities: numpy.ndarray, efforts: numpy.ndarray)
[summary]
- Parameters
positions (np.ndarray) – [description]
velocities (np.ndarray) – [description]
efforts (np.ndarray) – [description]
- class XFormPrimState(position: numpy.ndarray, orientation: numpy.ndarray)
[summary]
- Parameters
position (np.ndarray) – [description]
orientation (np.ndarray) – [description]
- class XFormPrimViewState(positions: Union[numpy.ndarray, torch.Tensor], orientations: Union[numpy.ndarray, torch.Tensor])
[summary]
- Parameters
positions (Union[np.ndarray, torch.Tensor]) – positions with shape of (N, 3).
orientations (Union[np.ndarray, torch.Tensor]) – quaternion representation of orientation (scalar first) with shape (N, 4).
Viewports Utils
- add_aov_to_viewport(viewport_api, aov_name: str)
- backproject_depth(depth_image: numpy.array, viewport_api: Any, max_clip_depth: float) numpy.array
Backproject depth image to image space
- Parameters
depth_image (np.array) – Depth image buffer
viewport_api (Any) – Handle to viewport api
max_clip_depth (float) – Depth values larger than this will be clipped
- Returns
[description]
- Return type
np.array
- create_viewport_for_camera(viewport_name: str, camera_prim_path: str, width: int = 1280, height: int = 720, position_x: int = 0, position_y: int = 0)
Create a new viewport and peg it to a specific camera specified by camera_prim_path. If the viewport already exists with the specified viewport_name, that viewport will be replaced with the new camera view.
- Parameters
viewport_name (str) – name of the viewport. If not provided, it will default to camera name.
camera_prim_path (str) – name of the prim path of the camera
width (int) – width of the viewport window, in pixels.
height (int) – height of the viewport window, in pixels.
position_x (int) – location x of the viewport window.
position_y (int) – location y of the viewport window.
- destroy_all_viewports(usd_context_name: Optional[str] = None, destroy_main_viewport=True)
Destroys all viewport windows
- Parameters
usd_context_name (str, optional) – usd context to use. Defaults to None.
destroy_main_viewport (bool, optional) – set to true to not destroy the default viewport. Defaults to False.
- get_id_from_index(index)
Get the viewport id for a given index. This function was added for backwards compatibility for VP2 as viewport IDs are not the same as the viewport index
- Parameters
index (_type_) – viewport index to retrieve ID for
- Returns
Returns None if window index was not found
- Return type
viewport id
- get_intrinsics_matrix(viewport_api: Any) numpy.ndarray
Get intrinsic matrix for the camera attached to a specific viewport
- Parameters
viewport (Any) – Handle to viewport api
- Returns
- the intrinsic matrix associated with the specified viewport
- The following image convention is assumed:
+x should point to the right in the image +y should point down in the image
- Return type
np.ndarray
- get_viewport_names(usd_context_name: Optional[str] = None) List[str]
Get list of all viewport names
- Parameters
usd_context_name (str, optional) – usd context to use. Defaults to None.
- Returns
List of viewport names
- Return type
List[str]
- get_window_from_id(id, usd_context_name: Optional[str] = None)
Find window that matches a given viewport id
- Parameters
id (_type_) – Viewport ID to get window for
usd_context_name (str, optional) – usd context to use. Defaults to None.
- Returns
Returns None if window with matching ID was not found
- Return type
Window
- project_depth_to_worldspace(depth_image: numpy.array, viewport_api: Any, max_clip_depth: float) List[carb._carb.Float3]
Project depth image to world space
- Parameters
depth_image (np.array) – Depth image buffer
viewport_api (Any) – Handle to viewport api
max_clip_depth (float) – Depth values larger than this will be clipped
- Returns
List of points from depth in world space
- Return type
List[carb.Float3]
- set_camera_view(eye: numpy.array, target: numpy.array, camera_prim_path: str = '/OmniverseKit_Persp', viewport_api=None) None
Set the location and target for a camera prim in the stage given its path
- Parameters
eye (np.ndarray) – Location of camera.
target (np.ndarray,) – Location of camera target.
camera_prim_path (str, optional) – Path to camera prim being set. Defaults to “/OmniverseKit_Persp”.
- set_intrinsics_matrix(viewport_api: Any, intrinsics_matrix: numpy.ndarray, focal_length: float = 1.0) None
Set intrinsic matrix for the camera attached to a specific viewport
Note
We assume cx and cy are centered in the camera horizontal_aperture_offset and vertical_aperture_offset are computed and set on the camera prim but are not used
- Parameters
viewport (Any) – Handle to viewport api
intrinsics_matrix (np.ndarray) – A 3x3 intrinsic matrix
focal_length (float, optional) – Default focal length to use when computing aperture values. Defaults to 1.0.
- Raises
ValueError – If intrinsic matrix is not a 3x3 matrix.
ValueError – If camera prim is not valid
XForms Utils
- clear_xform_ops(prim: pxr.Usd.Prim)
Remove all xform ops from input prim.
- Parameters
prim (Usd.Prim) – The input USD prim.
- get_local_pose(prim_path)
- get_world_pose(prim_path)
- reset_and_set_xform_ops(prim: pxr.Usd.Prim, translation: pxr.Gf.Vec3d, orientation: pxr.Gf.Quatd, scale: pxr.Gf.Vec3d = Gf.Vec3d(1.0, 1.0, 1.0))
Reset xform ops to isaac sim defaults, and set their values
- Parameters
prim (Usd.Prim) – Prim to reset
translation (Gf.Vec3d) – translation to set
orientation (Gf.Quatd) – orientation to set
scale (Gf.Vec3d, optional) – scale to set. Defaults to Gf.Vec3d([1.0, 1.0, 1.0]).
- reset_xform_ops(prim: pxr.Usd.Prim)
Reset xform ops for a prim to isaac sim defaults,
- Parameters
prim (Usd.Prim) – Prim to reset xform ops on
Numpy Utils
Rotations
- deg2rad(degree_value: numpy.ndarray, device=None) numpy.ndarray
_summary_
- Parameters
degree_value (np.ndarray) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
np.ndarray
- euler_angles_to_quats(euler_angles: numpy.ndarray, degrees: bool = False, extrinsic: bool = True, device=None) numpy.ndarray
Vectorized version of converting euler angles to quaternion (scalar first)
- Parameters
np.ndarray (euler_angles) – euler angles with shape (N, 3) or (3,) representation XYZ in extrinsic coordinates
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
degrees (bool, optional) – True if degrees, False if radians. Defaults to False.
- Returns
quaternions representation of the angles (N, 4) or (4,) - scalar first.
- Return type
np.ndarray
- gf_quat_to_tensor(orientation: Union[pxr.Gf.Quatd, pxr.Gf.Quatf, pxr.Gf.Quaternion], device=None) numpy.ndarray
Converts a pxr Quaternion type to a numpy array following [w, x, y, z] convention.
- Parameters
orientation (Union[Gf.Quatd, Gf.Quatf, Gf.Quaternion]) – [description]
- Returns
[description]
- Return type
np.ndarray
- quats_to_euler_angles(quaternions: numpy.ndarray, degrees: bool = False, extrinsic: bool = True, device=None) numpy.ndarray
Vectorized version of converting quaternions (scalar first) to euler angles
- Parameters
quaternions (np.ndarray) – quaternions with shape (N, 4) or (4,) - scalar first
degrees (bool, optional) – Return euler angles in degrees if True, radians if False. Defaults to False.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
Euler angles in extrinsic or intrinsic coordinates XYZ order with shape (N, 3) or (3,) corresponding to the quaternion rotations
- Return type
np.ndarray
- quats_to_rot_matrices(quaternions: numpy.ndarray, device=None) numpy.ndarray
Vectorized version of converting quaternions to rotation matrices
- Parameters
quaternions (np.ndarray) – quaternions with shape (N, 4) or (4,) and scalar first
- Returns
N Rotation matrices with shape (N, 3, 3) or (3, 3)
- Return type
np.ndarray
- quats_to_rotvecs(quaternions: numpy.ndarray, device=None) numpy.ndarray
Vectorized version of converting quaternions to rotation vectors
- Parameters
quaternions (np.ndarray) – quaternions with shape (N, 4) or (4,) and scalar first
- Returns
- N rotation vectors with shape (N,3) or (3,). The magnitude of the rotation vector describes the magnitude of the rotation.
The normalized rotation vector represents the axis of rotation.
- Return type
np.ndarray
- rad2deg(radian_value: numpy.ndarray, device=None) numpy.ndarray
_summary_
- Parameters
radian_value (np.ndarray) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
np.ndarray
- rot_matrices_to_quats(rotation_matrices: numpy.ndarray, device=None) numpy.ndarray
Vectorized version of converting rotation matrices to quaternions
- Parameters
rotation_matrices (np.ndarray) – N Rotation matrices with shape (N, 3, 3) or (3, 3)
- Returns
quaternion representation of the rotation matrices (N, 4) or (4,) - scalar first
- Return type
np.ndarray
- rotvecs_to_quats(rotation_vectors: numpy.ndarray, degrees: bool = False, device=None) numpy.ndarray
Vectorized version of converting rotation vectors to quaternions
- Parameters
rotation_vectors (np.ndarray) – N rotation vectors with shape (N, 3) or (3,). The magnitude of the rotation vector describes the magnitude of the rotation. The normalized rotation vector represents the axis of rotation.
degrees (bool) – The magnitude of the rotation vector will be interpreted as degrees if True, and radians if False. Defaults to False.
- Returns
quaternion representation of the rotation matrices (N, 4) or (4,) - scalar first
- Return type
np.ndarray
- wxyz2xyzw(q, ret_torch=False)
- xyzw2wxyz(q, ret_torch=False)
Maths
- cos(data)
- inverse(data)
- matmul(matrix_a, matrix_b)
- sin(data)
- transpose_2d(data)
Tensor
- as_type(data, dtype)
- assign(src, dst, indices)
- clone_tensor(data, device=None)
- convert(data, device=None, dtype='float32', indexed=None)
- create_tensor_from_list(data, dtype, device=None)
- create_zeros_tensor(shape, dtype, device=None)
- expand_dims(data, axis)
- move_data(data, device=None)
- pad(data, pad_width, mode='constant', value=None)
- resolve_indices(indices, count, device=None)
- tensor_cat(data, device=None, dim=- 1)
- tensor_stack(data, dim=0)
- to_list(data)
- to_numpy(data)
Transformations
- assign_pose(current_positions, current_orientations, positions, orientations, indices, device=None, pose=None)
- get_local_from_world(parent_transforms, positions, orientations, device=None)
- get_pose(positions, orientations, device=None)
- get_world_from_local(parent_transforms, translations, orientations, device=None)
- tf_matrices_from_poses(translations: numpy.ndarray, orientations: numpy.ndarray, device=None) numpy.ndarray
[summary]
- Parameters
translations (Union[np.ndarray, torch.Tensor]) – translations with shape (N, 3).
orientations (Union[np.ndarray, torch.Tensor]) – quaternion representation (scalar first) with shape (N, 4).
- Returns
transformation matrices with shape (N, 4, 4)
- Return type
Union[np.ndarray, torch.Tensor]
Torch Utils
Rotations
- compute_heading_and_up(torso_rotation: Tensor, inv_start_rot: Tensor, to_target: Tensor, vec0: Tensor, vec1: Tensor, up_idx: int) Tuple[Tensor, Tensor, Tensor, Tensor, Tensor]
- compute_rot(torso_quat, velocity, ang_velocity, targets, torso_positions, extrinsic: bool = True)
- deg2rad(degree_value: float, device=None) torch.Tensor
_summary_
- Parameters
degree_value (torch.Tensor) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
torch.Tensor
- euler_angles_to_quats(euler_angles: torch.Tensor, degrees: bool = False, extrinsic: bool = True, device=None) torch.Tensor
Vectorized version of converting euler angles to quaternion (scalar first)
- Parameters
euler_angles (Union[np.ndarray, torch.Tensor]) – euler angles with shape (N, 3)
degrees (bool, optional) – True if degrees, False if radians. Defaults to False.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
quaternions representation of the angles (N, 4) - scalar first.
- Return type
Union[np.ndarray, torch.Tensor]
- get_basis_vector(q, v)
- get_euler_xyz(q, extrinsic: bool = True)
- gf_quat_to_tensor(orientation: Union[pxr.Gf.Quatd, pxr.Gf.Quatf, pxr.Gf.Quaternion], device=None) torch.Tensor
Converts a pxr Quaternion type to a torch array (scalar first).
- Parameters
orientation (Union[Gf.Quatd, Gf.Quatf, Gf.Quaternion]) – [description]
- Returns
[description]
- Return type
torch.Tensor
- matrices_to_euler_angles(mat, extrinsic: bool = True)
- normalise_quat_in_pose(pose)
Takes a pose and normalises the quaternion portion of it.
- Parameters
pose – shape N, 7
- Returns
Pose with normalised quat. Shape N, 7
- normalize_angle(x)
- quat_apply(a, b)
- quat_axis(q: Tensor, axis: int = 0) Tensor
- quat_conjugate(a)
- quat_diff_rad(a: torch.Tensor, b: torch.Tensor) torch.Tensor
Get the difference in radians between two quaternions.
- Parameters
a – first quaternion, shape (N, 4)
b – second quaternion, shape (N, 4)
- Returns
Difference in radians, shape (N,)
- quat_from_angle_axis(angle, axis)
- quat_from_euler_xyz(roll, pitch, yaw, extrinsic: bool = True)
- quat_mul(a, b)
- quat_rotate(q, v)
- quat_rotate_inverse(q, v)
- quat_unit(a)
- quats_to_rot_matrices(quats)
- rad2deg(radian_value: torch.Tensor, device=None) torch.Tensor
_summary_
- Parameters
radian_value (torch.Tensor) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
torch.Tensor
- rot_matrices_to_quats(rotation_matrices: torch.Tensor, device=None) torch.Tensor
Vectorized version of converting rotation matrices to quaternions
- Parameters
rotation_matrices (torch.Tensor) – N Rotation matrices with shape (N, 3, 3) or (3, 3)
- Returns
quaternion representation of the rotation matrices (N, 4) or (4,) - scalar first
- Return type
torch.Tensor
- wxyz2xyzw(q)
- xyzw2wxyz(q)
Maths
- copysign(a: float, b: Tensor) Tensor
- cos(data)
- inverse(data)
- matmul(matrix_a, matrix_b)
- normalize(x, eps: float = 1e-09)
- scale(x, lower, upper)
- scale_transform(x: torch.Tensor, lower: torch.Tensor, upper: torch.Tensor) torch.Tensor
Normalizes a given input tensor to a range of [-1, 1].
@note It uses pytorch broadcasting functionality to deal with batched input.
- Parameters
x – Input tensor of shape (N, dims).
lower – The minimum value of the tensor. Shape (dims,)
upper – The maximum value of the tensor. Shape (dims,)
- Returns
Normalized transform of the tensor. Shape (N, dims)
- set_seed(seed, torch_deterministic=False)
set seed across modules
- sin(data)
- tensor_clamp(t, min_t, max_t)
- torch_rand_float(lower: float, upper: float, shape: Tuple[int, int], device: str) Tensor
- torch_random_dir_2(shape: Tuple[int, int], device: str) Tensor
- transpose_2d(data)
- unscale(x, lower, upper)
- unscale_np(x, lower, upper)
- unscale_transform(x: torch.Tensor, lower: torch.Tensor, upper: torch.Tensor) torch.Tensor
Denormalizes a given input tensor from range of [-1, 1] to (lower, upper).
@note It uses pytorch broadcasting functionality to deal with batched input.
- Parameters
x – Input tensor of shape (N, dims).
lower – The minimum value of the tensor. Shape (dims,)
upper – The maximum value of the tensor. Shape (dims,)
- Returns
Denormalized transform of the tensor. Shape (N, dims)
Tensor
- as_type(data, dtype)
- assign(src, dst, indices)
- clone_tensor(data, device)
- convert(data, device, dtype='float32', indexed=None)
- create_tensor_from_list(data, dtype, device=None)
- create_zeros_tensor(shape, dtype, device=None)
- expand_dims(data, axis)
- move_data(data, device)
- pad(data, pad_width, mode='constant', value=None)
- resolve_indices(indices, count, device)
- tensor_cat(data, device=None, dim=- 1)
- tensor_stack(data, dim=0)
- to_list(data)
- to_numpy(data)
Transformations
- assign_pose(current_positions, current_orientations, positions, orientations, indices, device, pose=None)
- get_local_from_world(parent_transforms, positions, orientations, device)
- get_pose(positions, orientations, device)
- get_world_from_local(parent_transforms, translations, orientations, device)
- get_world_from_local_position(pos_offset_local: torch.Tensor, pose_global: torch.Tensor)
Convert a point from the local frame to the global frame :param pos_offset_local: Point in local frame. Shape: [N, 3] :param pose_global: The spatial pose of this point. Shape: [N, 7]
- Returns
[N, 3]
- Return type
Position in the global frame. Shape
- normalise_quat_in_pose(pose)
Takes a pose and normalises the quaternion portion of it.
- Parameters
pose – shape N, 7
- Returns
Pose with normalised quat. Shape N, 7
- tf_apply(q, t, v)
- tf_combine(q1, t1, q2, t2)
- tf_inverse(q, t)
- tf_matrices_from_poses(translations: torch.Tensor, orientations: torch.Tensor, device=None) torch.Tensor
[summary]
- Parameters
translations (Union[np.ndarray, torch.Tensor]) – translations with shape (N, 3).
orientations (Union[np.ndarray, torch.Tensor]) – quaternion representation (scalar first) with shape (N, 4).
- Returns
transformation matrices with shape (N, 4, 4)
- Return type
Union[np.ndarray, torch.Tensor]
- tf_vector(q, v)
Warp Utils
Rotations
- compute_heading_and_up(torso_rotation: Tensor, inv_start_rot: Tensor, to_target: Tensor, vec0: Tensor, vec1: Tensor, up_idx: int) Tuple[Tensor, Tensor, Tensor, Tensor, Tensor]
- compute_rot(torso_quat, velocity, ang_velocity, targets, torso_positions, extrinsic: bool = True)
- deg2rad(degree_value: float, device=None) torch.Tensor
_summary_
- Parameters
degree_value (torch.Tensor) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
torch.Tensor
- euler_angles_to_quats(euler_angles: torch.Tensor, degrees: bool = False, extrinsic: bool = True, device=None) torch.Tensor
Vectorized version of converting euler angles to quaternion (scalar first)
- Parameters
euler_angles (Union[np.ndarray, torch.Tensor]) – euler angles with shape (N, 3)
degrees (bool, optional) – True if degrees, False if radians. Defaults to False.
extrinsic (bool, optional) – True if the euler angles follows the extrinsic angles convention (equivalent to ZYX ordering but returned in the reverse) and False if it follows the intrinsic angles conventions (equivalent to XYZ ordering). Defaults to True.
- Returns
quaternions representation of the angles (N, 4) - scalar first.
- Return type
Union[np.ndarray, torch.Tensor]
- get_basis_vector(q, v)
- get_euler_xyz(q, extrinsic: bool = True)
- gf_quat_to_tensor(orientation: Union[pxr.Gf.Quatd, pxr.Gf.Quatf, pxr.Gf.Quaternion], device=None) torch.Tensor
Converts a pxr Quaternion type to a torch array (scalar first).
- Parameters
orientation (Union[Gf.Quatd, Gf.Quatf, Gf.Quaternion]) – [description]
- Returns
[description]
- Return type
torch.Tensor
- matrices_to_euler_angles(mat, extrinsic: bool = True)
- normalise_quat_in_pose(pose)
Takes a pose and normalises the quaternion portion of it.
- Parameters
pose – shape N, 7
- Returns
Pose with normalised quat. Shape N, 7
- normalize_angle(x)
- quat_apply(a, b)
- quat_axis(q: Tensor, axis: int = 0) Tensor
- quat_conjugate(a)
- quat_diff_rad(a: torch.Tensor, b: torch.Tensor) torch.Tensor
Get the difference in radians between two quaternions.
- Parameters
a – first quaternion, shape (N, 4)
b – second quaternion, shape (N, 4)
- Returns
Difference in radians, shape (N,)
- quat_from_angle_axis(angle, axis)
- quat_from_euler_xyz(roll, pitch, yaw, extrinsic: bool = True)
- quat_mul(a, b)
- quat_rotate(q, v)
- quat_rotate_inverse(q, v)
- quat_unit(a)
- quats_to_rot_matrices(quats)
- rad2deg(radian_value: torch.Tensor, device=None) torch.Tensor
_summary_
- Parameters
radian_value (torch.Tensor) – _description_
device (_type_, optional) – _description_. Defaults to None.
- Returns
_description_
- Return type
torch.Tensor
- rot_matrices_to_quats(rotation_matrices: torch.Tensor, device=None) torch.Tensor
Vectorized version of converting rotation matrices to quaternions
- Parameters
rotation_matrices (torch.Tensor) – N Rotation matrices with shape (N, 3, 3) or (3, 3)
- Returns
quaternion representation of the rotation matrices (N, 4) or (4,) - scalar first
- Return type
torch.Tensor
- wxyz2xyzw(q)
- xyzw2wxyz(q)
Tensor
- as_type(data, dtype)
- assign(src, dst, indices)
- clone_tensor(data, device)
- convert(data, device, dtype='float32', indexed=None)
- create_tensor_from_list(data, dtype, device=None)
- create_zeros_tensor(shape, dtype, device=None)
- expand_dims(data, axis)
- move_data(data, device)
- pad(data, pad_width, mode='constant', value=None)
- resolve_indices(indices, count, device)
- tensor_cat(data, device=None, dim=- 1)
- tensor_stack(data, dim=0)
- to_list(data)
- to_numpy(data)
Transformations
- assign_pose(current_positions, current_orientations, positions, orientations, indices, device, pose=None)
- get_local_from_world(parent_transforms, positions, orientations, device)
- get_pose(positions, orientations, device)
- get_world_from_local(parent_transforms, translations, orientations, device)
- get_world_from_local_position(pos_offset_local: torch.Tensor, pose_global: torch.Tensor)
Convert a point from the local frame to the global frame :param pos_offset_local: Point in local frame. Shape: [N, 3] :param pose_global: The spatial pose of this point. Shape: [N, 7]
- Returns
[N, 3]
- Return type
Position in the global frame. Shape
- normalise_quat_in_pose(pose)
Takes a pose and normalises the quaternion portion of it.
- Parameters
pose – shape N, 7
- Returns
Pose with normalised quat. Shape N, 7
- tf_apply(q, t, v)
- tf_combine(q1, t1, q2, t2)
- tf_inverse(q, t)
- tf_matrices_from_poses(translations: torch.Tensor, orientations: torch.Tensor, device=None) torch.Tensor
[summary]
- Parameters
translations (Union[np.ndarray, torch.Tensor]) – translations with shape (N, 3).
orientations (Union[np.ndarray, torch.Tensor]) – quaternion representation (scalar first) with shape (N, 4).
- Returns
transformation matrices with shape (N, 4, 4)
- Return type
Union[np.ndarray, torch.Tensor]
- tf_vector(q, v)