We have now released v0.3.0! Please use the latest version for the best experience.

orbit.assets

Contents

orbit.assets#

Sub-package for different assets, such as rigid objects and articulations.

An asset is a physical object that can be spawned in the simulation. The class handles both the spawning of the asset into the USD stage as well as initialization of necessary physics handles to interact with the asset.

Upon construction of the asset instance, the prim corresponding to the asset is spawned into the USD stage if the spawn configuration is not None. The spawn configuration is defined in the AssetBaseCfg.spawn attribute. In case the configured AssetBaseCfg.prim_path is an expression, then the prim is spawned at all the matching paths. Otherwise, a single prim is spawned at the configured path. For more information on the spawn configuration, see the omni.isaac.orbit.sim.spawners module.

The asset class also registers callbacks for the stage play/stop events. These are used to construct the physics handles for the asset as the physics engine is only available when the stage is playing. Additionally, the class registers a callback for debug visualization of the asset. This can be enabled by setting the AssetBaseCfg.debug_vis attribute to True.

The asset class follows the following naming convention for its methods:

  • set_xxx(): These are used to only set the buffers into the data instance. However, they do not write the data into the simulator. The writing of data only happens when the write_data_to_sim() method is called.

  • write_xxx_to_sim(): These are used to set the buffers into the data instance and write the corresponding data into the simulator as well.

  • update(dt): These are used to update the buffers in the data instance. This should be called after a simulation step is performed.

The main reason to separate the set and write operations is to provide flexibility to the user when they need to perform a post-processing operation of the buffers before applying them into the simulator. A common example for this is dealing with explicit actuator models where the specified joint targets are not directly applied to the simulator but are instead used to compute the corresponding actuator torques.

Classes

AssetBase

The base interface class for assets.

AssetBaseCfg

The base configuration class for an asset's parameters.

RigidObject

A rigid object asset class.

RigidObjectData

Data container for a rigid object.

RigidObjectCfg

Configuration parameters for a rigid object.

Articulation

An articulation asset class.

ArticulationData

Data container for an articulation.

ArticulationCfg

Configuration parameters for an articulation.

Asset Base#

class omni.isaac.orbit.assets.AssetBase[source]#

The base interface class for assets.

An asset corresponds to any physics-enabled object that can be spawned in the simulation. These include rigid objects, articulated objects, deformable objects etc. The core functionality of an asset is to provide a set of buffers that can be used to interact with the simulator. The buffers are updated by the asset class and can be written into the simulator using the their respective write methods. This allows a convenient way to perform post-processing operations on the buffers before writing them into the simulator and obtaining the corresponding simulation results.

The class handles both the spawning of the asset into the USD stage as well as initialization of necessary physics handles to interact with the asset. Upon construction of the asset instance, the prim corresponding to the asset is spawned into the USD stage if the spawn configuration is not None. The spawn configuration is defined in the AssetBaseCfg.spawn attribute. In case the configured AssetBaseCfg.prim_path is an expression, then the prim is spawned at all the matching paths. Otherwise, a single prim is spawned at the configured path. For more information on the spawn configuration, see the omni.isaac.orbit.sim.spawners module.

Unlike Isaac Sim interface, where one usually needs to call the omni.isaac.core.prims.XFormPrimView.initialize() method to initialize the PhysX handles, the asset class automatically initializes and invalidates the PhysX handles when the stage is played/stopped. This is done by registering callbacks for the stage play/stop events.

Additionally, the class registers a callback for debug visualization of the asset if a debug visualization is implemented in the asset class. This can be enabled by setting the AssetBaseCfg.debug_vis attribute to True. The debug visualization is implemented through the _set_debug_vis_impl() and _debug_vis_callback() methods.

Methods:

__init__(cfg)

Initialize the asset base.

set_debug_vis(debug_vis)

Sets whether to visualize the asset data.

reset([env_ids])

Resets all internal buffers of selected environments.

write_data_to_sim()

Writes data to the simulator.

update(dt)

Update the internal buffers.

Attributes:

num_instances

Number of instances of the asset.

device

Memory device for computation.

data

Data related to the asset.

has_debug_vis_implementation

Whether the asset has a debug visualization implemented.

__init__(cfg: AssetBaseCfg)[source]#

Initialize the asset base.

Parameters:

cfg – The configuration class for the asset.

Raises:

RuntimeError – If no prims found at input prim path or prim path expression.

abstract property num_instances: int#

Number of instances of the asset.

This is equal to the number of asset instances per environment multiplied by the number of environments.

property device: str#

Memory device for computation.

abstract property data: Any#

Data related to the asset.

property has_debug_vis_implementation: bool#

Whether the asset has a debug visualization implemented.

set_debug_vis(debug_vis: bool) bool[source]#

Sets whether to visualize the asset data.

Parameters:

debug_vis – Whether to visualize the asset data.

Returns:

Whether the debug visualization was successfully set. False if the asset does not support debug visualization.

abstract reset(env_ids: Sequence[int] | None = None)[source]#

Resets all internal buffers of selected environments.

Parameters:

env_ids – The indices of the object to reset. Defaults to None (all instances).

abstract write_data_to_sim()[source]#

Writes data to the simulator.

abstract update(dt: float)[source]#

Update the internal buffers.

The time step dt is used to compute numerical derivatives of quantities such as joint accelerations which are not provided by the simulator.

Parameters:

dt – The amount of time passed from last update call.

class omni.isaac.orbit.assets.AssetBaseCfg[source]#

The base configuration class for an asset’s parameters.

Please see the AssetBase class for more information on the asset class.

Classes:

InitialStateCfg

Initial state of the asset.

Attributes:

prim_path

Prim path (or expression) to the asset.

spawn

Spawn configuration for the asset.

init_state

Initial state of the rigid object.

collision_group

Collision group of the asset.

debug_vis

Whether to enable debug visualization for the asset.

class InitialStateCfg[source]#

Initial state of the asset.

This defines the default initial state of the asset when it is spawned into the simulation, as well as the default state when the simulation is reset.

After parsing the initial state, the asset class stores this information in the data attribute of the asset class. This can then be accessed by the user to modify the state of the asset during the simulation, for example, at resets.

Attributes:

pos

Position of the root in simulation world frame.

rot

Quaternion rotation (w, x, y, z) of the root in simulation world frame.

pos: tuple[float, float, float]#

Position of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

rot: tuple[float, float, float, float]#

Quaternion rotation (w, x, y, z) of the root in simulation world frame. Defaults to (1.0, 0.0, 0.0, 0.0).

prim_path: str#

Prim path (or expression) to the asset.

Note

The expression can contain the environment namespace regex {ENV_REGEX_NS} which will be replaced with the environment namespace.

Example: {ENV_REGEX_NS}/Robot will be replaced with /World/envs/env_.*/Robot.

spawn: SpawnerCfg | None#

Spawn configuration for the asset. Defaults to None.

If None, then no prims are spawned by the asset class. Instead, it is assumed that the asset is already present in the scene.

init_state: InitialStateCfg#

Initial state of the rigid object. Defaults to identity pose.

collision_group: Literal[0, -1]#

Collision group of the asset. Defaults to 0.

  • -1: global collision group (collides with all assets in the scene).

  • 0: local collision group (collides with other assets in the same environment).

debug_vis: bool#

Whether to enable debug visualization for the asset. Defaults to False.

Rigid Object#

class omni.isaac.orbit.assets.RigidObject[source]#

Bases: AssetBase

A rigid object asset class.

Rigid objects are assets comprising of rigid bodies. They can be used to represent dynamic objects such as boxes, spheres, etc. A rigid body is described by its pose, velocity and mass distribution.

For an asset to be considered a rigid object, the root prim of the asset must have the USD RigidBodyAPI applied to it. This API is used to define the simulation properties of the rigid body. On playing the simulation, the physics engine will automatically register the rigid body and create a corresponding rigid body handle. This handle can be accessed using the root_physx_view attribute.

Note

For users familiar with Isaac Sim, the PhysX view class API is not the exactly same as Isaac Sim view class API. Similar to Orbit, Isaac Sim wraps around the PhysX view API. However, as of now (2023.1 release), we see a large difference in initializing the view classes in Isaac Sim. This is because the view classes in Isaac Sim perform additional USD-related operations which are slow and also not required.

Attributes:

cfg

Configuration instance for the rigid object.

data

Data related to the asset.

num_instances

Number of instances of the asset.

num_bodies

Number of bodies in the asset.

body_names

Ordered names of bodies in articulation.

root_physx_view

Rigid body view for the asset (PhysX).

body_physx_view

Rigid body view for the asset (PhysX).

device

Memory device for computation.

has_debug_vis_implementation

Whether the asset has a debug visualization implemented.

Methods:

__init__(cfg)

Initialize the rigid object.

reset([env_ids])

Resets all internal buffers of selected environments.

write_data_to_sim()

Write external wrench to the simulation.

update(dt)

Update the internal buffers.

find_bodies(name_keys[, preserve_order])

Find bodies in the articulation based on the name keys.

write_root_state_to_sim(root_state[, env_ids])

Set the root state over selected environment indices into the simulation.

write_root_pose_to_sim(root_pose[, env_ids])

Set the root pose over selected environment indices into the simulation.

write_root_velocity_to_sim(root_velocity[, ...])

Set the root velocity over selected environment indices into the simulation.

set_external_force_and_torque(forces, torques)

Set external force and torque to apply on the asset's bodies in their local frame.

set_debug_vis(debug_vis)

Sets whether to visualize the asset data.

cfg: RigidObjectCfg#

Configuration instance for the rigid object.

__init__(cfg: RigidObjectCfg)[source]#

Initialize the rigid object.

Parameters:

cfg – A configuration instance.

property data: RigidObjectData#

Data related to the asset.

property num_instances: int#

Number of instances of the asset.

This is equal to the number of asset instances per environment multiplied by the number of environments.

property num_bodies: int#

Number of bodies in the asset.

property body_names: list[str]#

Ordered names of bodies in articulation.

property root_physx_view: omni.physics.tensors.impl.api.RigidBodyView#

Rigid body view for the asset (PhysX).

Note

Use this view with caution. It requires handling of tensors in a specific way.

property body_physx_view: omni.physics.tensors.impl.api.RigidBodyView#

Rigid body view for the asset (PhysX).

Deprecated since version v0.3.0: The attribute ‘body_physx_view’ will be removed in v0.4.0. Please use root_physx_view instead.

reset(env_ids: Sequence[int] | None = None)[source]#

Resets all internal buffers of selected environments.

Parameters:

env_ids – The indices of the object to reset. Defaults to None (all instances).

write_data_to_sim()[source]#

Write external wrench to the simulation.

Note

We write external wrench to the simulation here since this function is called before the simulation step. This ensures that the external wrench is applied at every simulation step.

update(dt: float)[source]#

Update the internal buffers.

The time step dt is used to compute numerical derivatives of quantities such as joint accelerations which are not provided by the simulator.

Parameters:

dt – The amount of time passed from last update call.

find_bodies(name_keys: str | Sequence[str], preserve_order: bool = False) tuple[list[int], list[str]][source]#

Find bodies in the articulation based on the name keys.

Please check the omni.isaac.orbit.utils.string_utils.resolve_matching_names() function for more information on the name matching.

Parameters:
  • name_keys – A regular expression or a list of regular expressions to match the body names.

  • preserve_order – Whether to preserve the order of the name keys in the output. Defaults to False.

Returns:

A tuple of lists containing the body indices and names.

write_root_state_to_sim(root_state: torch.Tensor, env_ids: Sequence[int] | None = None)[source]#

Set the root state over selected environment indices into the simulation.

The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear and angular velocity. All the quantities are in the simulation frame.

Parameters:
  • root_state – Root state in simulation frame. Shape is (len(env_ids), 13).

  • env_ids – Environment indices. If None, then all indices are used.

write_root_pose_to_sim(root_pose: torch.Tensor, env_ids: Sequence[int] | None = None)[source]#

Set the root pose over selected environment indices into the simulation.

The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).

Parameters:
  • root_pose – Root poses in simulation frame. Shape is (len(env_ids), 7).

  • env_ids – Environment indices. If None, then all indices are used.

write_root_velocity_to_sim(root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None)[source]#

Set the root velocity over selected environment indices into the simulation.

Parameters:
  • root_velocity – Root velocities in simulation frame. Shape is (len(env_ids), 6).

  • env_ids – Environment indices. If None, then all indices are used.

set_external_force_and_torque(forces: torch.Tensor, torques: torch.Tensor, body_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Set external force and torque to apply on the asset’s bodies in their local frame.

For many applications, we want to keep the applied external force on rigid bodies constant over a period of time (for instance, during the policy control). This function allows us to store the external force and torque into buffers which are then applied to the simulation at every step.

Caution

If the function is called with empty forces and torques, then this function disables the application of external wrench to the simulation.

# example of disabling external wrench
asset.set_external_force_and_torque(forces=torch.zeros(0, 3), torques=torch.zeros(0, 3))

Note

This function does not apply the external wrench to the simulation. It only fills the buffers with the desired values. To apply the external wrench, call the write_data_to_sim() function right before the simulation step.

Parameters:
  • forces – External forces in bodies’ local frame. Shape is (len(env_ids), len(body_ids), 3).

  • torques – External torques in bodies’ local frame. Shape is (len(env_ids), len(body_ids), 3).

  • body_ids – Body indices to apply external wrench to. Defaults to None (all bodies).

  • env_ids – Environment indices to apply external wrench to. Defaults to None (all instances).

property device: str#

Memory device for computation.

property has_debug_vis_implementation: bool#

Whether the asset has a debug visualization implemented.

set_debug_vis(debug_vis: bool) bool#

Sets whether to visualize the asset data.

Parameters:

debug_vis – Whether to visualize the asset data.

Returns:

Whether the debug visualization was successfully set. False if the asset does not support debug visualization.

class omni.isaac.orbit.assets.RigidObjectData[source]#

Bases: object

Data container for a rigid object.

Attributes:

body_names

Body names in the order parsed by the simulation view.

default_root_state

Default root state [pos, quat, lin_vel, ang_vel] in local environment frame.

root_state_w

Root state [pos, quat, lin_vel, ang_vel] in simulation world frame.

root_vel_b

Root velocity [lin_vel, ang_vel] in base frame.

projected_gravity_b

Projection of the gravity direction on base frame.

heading_w

Yaw heading of the base frame (in radians).

body_state_w

State of all bodies [pos, quat, lin_vel, ang_vel] in simulation world frame.

body_acc_w

Acceleration of all bodies.

root_pos_w

Root position in simulation world frame.

root_quat_w

Root orientation (w, x, y, z) in simulation world frame.

root_vel_w

Root velocity in simulation world frame.

root_lin_vel_w

Root linear velocity in simulation world frame.

root_ang_vel_w

Root angular velocity in simulation world frame.

root_lin_vel_b

Root linear velocity in base frame.

root_ang_vel_b

Root angular velocity in base world frame.

body_pos_w

Positions of all bodies in simulation world frame.

body_quat_w

Orientation (w, x, y, z) of all bodies in simulation world frame.

body_vel_w

Velocity of all bodies in simulation world frame.

body_lin_vel_w

Linear velocity of all bodies in simulation world frame.

body_ang_vel_w

Angular velocity of all bodies in simulation world frame.

body_lin_acc_w

Linear acceleration of all bodies in simulation world frame.

body_ang_acc_w

Angular acceleration of all bodies in simulation world frame.

body_names: list[str] = None#

Body names in the order parsed by the simulation view.

default_root_state: torch.Tensor = None#

Default root state [pos, quat, lin_vel, ang_vel] in local environment frame. Shape is (num_instances, 13).

root_state_w: torch.Tensor = None#

Root state [pos, quat, lin_vel, ang_vel] in simulation world frame. Shape is (num_instances, 13).

root_vel_b: torch.Tensor = None#

Root velocity [lin_vel, ang_vel] in base frame. Shape is (num_instances, 6).

projected_gravity_b: torch.Tensor = None#

Projection of the gravity direction on base frame. Shape is (num_instances, 3).

heading_w: torch.Tensor = None#

Yaw heading of the base frame (in radians). Shape is (num_instances,).

Note

This quantity is computed by assuming that the forward-direction of the base frame is along x-direction, i.e. \((1, 0, 0)\).

body_state_w: torch.Tensor = None#

State of all bodies [pos, quat, lin_vel, ang_vel] in simulation world frame. Shape is (num_instances, num_bodies, 13).

body_acc_w: torch.Tensor = None#

Acceleration of all bodies. Shape is (num_instances, num_bodies, 6).

Note

This quantity is computed based on the rigid body state from the last step.

property root_pos_w: torch.Tensor#

Root position in simulation world frame. Shape is (num_instances, 3).

property root_quat_w: torch.Tensor#

Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4).

property root_vel_w: torch.Tensor#

Root velocity in simulation world frame. Shape is (num_instances, 6).

property root_lin_vel_w: torch.Tensor#

Root linear velocity in simulation world frame. Shape is (num_instances, 3).

property root_ang_vel_w: torch.Tensor#

Root angular velocity in simulation world frame. Shape is (num_instances, 3).

property root_lin_vel_b: torch.Tensor#

Root linear velocity in base frame. Shape is (num_instances, 3).

property root_ang_vel_b: torch.Tensor#

Root angular velocity in base world frame. Shape is (num_instances, 3).

property body_pos_w: torch.Tensor#

Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_quat_w: torch.Tensor#

Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).

property body_vel_w: torch.Tensor#

Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).

property body_lin_vel_w: torch.Tensor#

Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_ang_vel_w: torch.Tensor#

Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_lin_acc_w: torch.Tensor#

Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_ang_acc_w: torch.Tensor#

Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

class omni.isaac.orbit.assets.RigidObjectCfg[source]#

Bases: AssetBaseCfg

Configuration parameters for a rigid object.

Classes:

InitialStateCfg

Initial state of the rigid body.

Attributes:

init_state

Initial state of the rigid object.

class InitialStateCfg[source]#

Bases: InitialStateCfg

Initial state of the rigid body.

Attributes:

lin_vel

Linear velocity of the root in simulation world frame.

ang_vel

Angular velocity of the root in simulation world frame.

lin_vel: tuple[float, float, float]#

Linear velocity of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

ang_vel: tuple[float, float, float]#

Angular velocity of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

pos: tuple[float, float, float]#

Position of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

rot: tuple[float, float, float, float]#

Quaternion rotation (w, x, y, z) of the root in simulation world frame. Defaults to (1.0, 0.0, 0.0, 0.0).

prim_path: str#

Prim path (or expression) to the asset.

Note

The expression can contain the environment namespace regex {ENV_REGEX_NS} which will be replaced with the environment namespace.

Example: {ENV_REGEX_NS}/Robot will be replaced with /World/envs/env_.*/Robot.

spawn: SpawnerCfg | None#

Spawn configuration for the asset. Defaults to None.

If None, then no prims are spawned by the asset class. Instead, it is assumed that the asset is already present in the scene.

collision_group: Literal[0, -1]#

Collision group of the asset. Defaults to 0.

  • -1: global collision group (collides with all assets in the scene).

  • 0: local collision group (collides with other assets in the same environment).

debug_vis: bool#

Whether to enable debug visualization for the asset. Defaults to False.

init_state: InitialStateCfg#

Initial state of the rigid object. Defaults to identity pose with zero velocity.

Articulation#

class omni.isaac.orbit.assets.Articulation[source]#

Bases: RigidObject

An articulation asset class.

An articulation is a collection of rigid bodies connected by joints. The joints can be either fixed or actuated. The joints can be of different types, such as revolute, prismatic, D-6, etc. However, the articulation class has currently been tested with revolute and prismatic joints. The class supports both floating-base and fixed-base articulations. The type of articulation is determined based on the root joint of the articulation. If the root joint is fixed, then the articulation is considered a fixed-base system. Otherwise, it is considered a floating-base system. This can be checked using the Articulation.is_fixed_base attribute.

For an asset to be considered an articulation, the root prim of the asset must have the USD ArticulationRootAPI. This API is used to define the sub-tree of the articulation using the reduced coordinate formulation. On playing the simulation, the physics engine parses the articulation root prim and creates the corresponding articulation in the physics engine. The articulation root prim can be specified using the AssetBaseCfg.prim_path attribute.

The articulation class is a subclass of the RigidObject class. Therefore, it inherits all the functionality of the rigid object class. In case of an articulation, the root_physx_view attribute corresponds to the articulation root view and can be used to access the articulation related data.

The articulation class also provides the functionality to augment the simulation of an articulated system with custom actuator models. These models can either be explicit or implicit, as detailed in the omni.isaac.orbit.actuators module. The actuator models are specified using the ArticulationCfg.actuators attribute. These are then parsed and used to initialize the corresponding actuator models, when the simulation is played.

During the simulation step, the articulation class first applies the actuator models to compute the joint commands based on the user-specified targets. These joint commands are then applied into the simulation. The joint commands can be either position, velocity, or effort commands. As an example, the following snippet shows how this can be used for position commands:

# an example instance of the articulation class
my_articulation = Articulation(cfg)

# set joint position targets
my_articulation.set_joint_position_target(position)
# propagate the actuator models and apply the computed commands into the simulation
my_articulation.write_data_to_sim()

# step the simulation using the simulation context
sim_context.step()

# update the articulation state, where dt is the simulation time step
my_articulation.update(dt)

Attributes:

cfg

Configuration instance for the articulations.

data

Data related to the asset.

is_fixed_base

Whether the articulation is a fixed-base or floating-base system.

num_joints

Number of joints in articulation.

num_fixed_tendons

Number of fixed tendons in articulation.

num_bodies

Number of bodies in articulation.

joint_names

Ordered names of joints in articulation.

body_names

Ordered names of bodies in articulation.

root_physx_view

Articulation view for the asset (PhysX).

body_physx_view

Rigid body view for the asset (PhysX).

device

Memory device for computation.

has_debug_vis_implementation

Whether the asset has a debug visualization implemented.

num_instances

Number of instances of the asset.

Methods:

__init__(cfg)

Initialize the articulation.

reset([env_ids])

Resets all internal buffers of selected environments.

write_data_to_sim()

Write external wrenches and joint commands to the simulation.

update(dt)

Update the internal buffers.

find_joints(name_keys[, joint_subset, ...])

Find joints in the articulation based on the name keys.

set_external_force_and_torque(forces, torques)

Set external force and torque to apply on the asset's bodies in their local frame.

write_root_pose_to_sim(root_pose[, env_ids])

Set the root pose over selected environment indices into the simulation.

write_root_velocity_to_sim(root_velocity[, ...])

Set the root velocity over selected environment indices into the simulation.

write_joint_state_to_sim(position, velocity)

Write joint positions and velocities to the simulation.

write_joint_stiffness_to_sim(stiffness[, ...])

Write joint stiffness into the simulation.

write_joint_damping_to_sim(damping[, ...])

Write joint damping into the simulation.

write_joint_effort_limit_to_sim(limits[, ...])

Write joint effort limits into the simulation.

write_joint_armature_to_sim(armature[, ...])

Write joint armature into the simulation.

write_joint_friction_to_sim(joint_friction)

Write joint friction into the simulation.

set_joint_position_target(target[, ...])

Set joint position targets into internal buffers.

set_joint_velocity_target(target[, ...])

Set joint velocity targets into internal buffers.

set_joint_effort_target(target[, joint_ids, ...])

Set joint efforts into internal buffers.

find_bodies(name_keys[, preserve_order])

Find bodies in the articulation based on the name keys.

set_debug_vis(debug_vis)

Sets whether to visualize the asset data.

write_root_state_to_sim(root_state[, env_ids])

Set the root state over selected environment indices into the simulation.

cfg: ArticulationCfg#

Configuration instance for the articulations.

__init__(cfg: ArticulationCfg)[source]#

Initialize the articulation.

Parameters:

cfg – A configuration instance.

property data: ArticulationData#

Data related to the asset.

property is_fixed_base: bool#

Whether the articulation is a fixed-base or floating-base system.

property num_joints: int#

Number of joints in articulation.

property num_fixed_tendons: int#

Number of fixed tendons in articulation.

property num_bodies: int#

Number of bodies in articulation.

property joint_names: list[str]#

Ordered names of joints in articulation.

property body_names: list[str]#

Ordered names of bodies in articulation.

property root_physx_view: omni.physics.tensors.impl.api.ArticulationView#

Articulation view for the asset (PhysX).

Note

Use this view with caution. It requires handling of tensors in a specific way.

property body_physx_view: omni.physics.tensors.impl.api.RigidBodyView#

Rigid body view for the asset (PhysX).

Deprecated since version v0.3.0: In previous versions, this attribute returned the rigid body view over all the links of the articulation. However, this led to confusion with the link ordering as they were not ordered in the same way as the articulation view.

Therefore, this attribute will be removed in v0.4.0. Please use the root_physx_view attribute instead.

reset(env_ids: Sequence[int] | None = None)[source]#

Resets all internal buffers of selected environments.

Parameters:

env_ids – The indices of the object to reset. Defaults to None (all instances).

write_data_to_sim()[source]#

Write external wrenches and joint commands to the simulation.

If any explicit actuators are present, then the actuator models are used to compute the joint commands. Otherwise, the joint commands are directly set into the simulation.

update(dt: float)[source]#

Update the internal buffers.

The time step dt is used to compute numerical derivatives of quantities such as joint accelerations which are not provided by the simulator.

Parameters:

dt – The amount of time passed from last update call.

find_joints(name_keys: str | Sequence[str], joint_subset: list[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#

Find joints in the articulation based on the name keys.

Please see the omni.isaac.orbit.utils.string.resolve_matching_names() function for more information on the name matching.

Parameters:
  • name_keys – A regular expression or a list of regular expressions to match the joint names.

  • joint_subset – A subset of joints to search for. Defaults to None, which means all joints in the articulation are searched.

  • preserve_order – Whether to preserve the order of the name keys in the output. Defaults to False.

Returns:

A tuple of lists containing the joint indices and names.

set_external_force_and_torque(forces: torch.Tensor, torques: torch.Tensor, body_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Set external force and torque to apply on the asset’s bodies in their local frame.

For many applications, we want to keep the applied external force on rigid bodies constant over a period of time (for instance, during the policy control). This function allows us to store the external force and torque into buffers which are then applied to the simulation at every step.

Caution

If the function is called with empty forces and torques, then this function disables the application of external wrench to the simulation.

# example of disabling external wrench
asset.set_external_force_and_torque(forces=torch.zeros(0, 3), torques=torch.zeros(0, 3))

Note

This function does not apply the external wrench to the simulation. It only fills the buffers with the desired values. To apply the external wrench, call the write_data_to_sim() function right before the simulation step.

Parameters:
  • forces – External forces in bodies’ local frame. Shape is (len(env_ids), len(body_ids), 3).

  • torques – External torques in bodies’ local frame. Shape is (len(env_ids), len(body_ids), 3).

  • body_ids – Body indices to apply external wrench to. Defaults to None (all bodies).

  • env_ids – Environment indices to apply external wrench to. Defaults to None (all instances).

write_root_pose_to_sim(root_pose: torch.Tensor, env_ids: Sequence[int] | None = None)[source]#

Set the root pose over selected environment indices into the simulation.

The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).

Parameters:
  • root_pose – Root poses in simulation frame. Shape is (len(env_ids), 7).

  • env_ids – Environment indices. If None, then all indices are used.

write_root_velocity_to_sim(root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None)[source]#

Set the root velocity over selected environment indices into the simulation.

Parameters:
  • root_velocity – Root velocities in simulation frame. Shape is (len(env_ids), 6).

  • env_ids – Environment indices. If None, then all indices are used.

write_joint_state_to_sim(position: torch.Tensor, velocity: torch.Tensor, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | slice | None = None)[source]#

Write joint positions and velocities to the simulation.

Parameters:
  • position – Joint positions. Shape is (len(env_ids), len(joint_ids)).

  • velocity – Joint velocities. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the targets for. Defaults to None (all joints).

  • env_ids – The environment indices to set the targets for. Defaults to None (all environments).

write_joint_stiffness_to_sim(stiffness: torch.Tensor | float, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Write joint stiffness into the simulation.

Parameters:
  • stiffness – Joint stiffness. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the stiffness for. Defaults to None (all joints).

  • env_ids – The environment indices to set the stiffness for. Defaults to None (all environments).

write_joint_damping_to_sim(damping: torch.Tensor | float, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Write joint damping into the simulation.

Parameters:
  • damping – Joint damping. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the damping for. Defaults to None (all joints).

  • env_ids – The environment indices to set the damping for. Defaults to None (all environments).

write_joint_effort_limit_to_sim(limits: torch.Tensor | float, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Write joint effort limits into the simulation.

Parameters:
  • limits – Joint torque limits. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the joint torque limits for. Defaults to None (all joints).

  • env_ids – The environment indices to set the joint torque limits for. Defaults to None (all environments).

write_joint_armature_to_sim(armature: torch.Tensor | float, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Write joint armature into the simulation.

Parameters:
  • armature – Joint armature. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the joint torque limits for. Defaults to None (all joints).

  • env_ids – The environment indices to set the joint torque limits for. Defaults to None (all environments).

write_joint_friction_to_sim(joint_friction: torch.Tensor | float, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Write joint friction into the simulation.

Parameters:
  • joint_friction – Joint friction. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the joint torque limits for. Defaults to None (all joints).

  • env_ids – The environment indices to set the joint torque limits for. Defaults to None (all environments).

set_joint_position_target(target: torch.Tensor, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Set joint position targets into internal buffers.

Note

This function does not apply the joint targets to the simulation. It only fills the buffers with the desired values. To apply the joint targets, call the write_data_to_sim() function.

Parameters:
  • target – Joint position targets. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the targets for. Defaults to None (all joints).

  • env_ids – The environment indices to set the targets for. Defaults to None (all environments).

set_joint_velocity_target(target: torch.Tensor, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Set joint velocity targets into internal buffers.

Note

This function does not apply the joint targets to the simulation. It only fills the buffers with the desired values. To apply the joint targets, call the write_data_to_sim() function.

Parameters:
  • target – Joint velocity targets. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the targets for. Defaults to None (all joints).

  • env_ids – The environment indices to set the targets for. Defaults to None (all environments).

set_joint_effort_target(target: torch.Tensor, joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None)[source]#

Set joint efforts into internal buffers.

Note

This function does not apply the joint targets to the simulation. It only fills the buffers with the desired values. To apply the joint targets, call the write_data_to_sim() function.

Parameters:
  • target – Joint effort targets. Shape is (len(env_ids), len(joint_ids)).

  • joint_ids – The joint indices to set the targets for. Defaults to None (all joints).

  • env_ids – The environment indices to set the targets for. Defaults to None (all environments).

property device: str#

Memory device for computation.

find_bodies(name_keys: str | Sequence[str], preserve_order: bool = False) tuple[list[int], list[str]]#

Find bodies in the articulation based on the name keys.

Please check the omni.isaac.orbit.utils.string_utils.resolve_matching_names() function for more information on the name matching.

Parameters:
  • name_keys – A regular expression or a list of regular expressions to match the body names.

  • preserve_order – Whether to preserve the order of the name keys in the output. Defaults to False.

Returns:

A tuple of lists containing the body indices and names.

property has_debug_vis_implementation: bool#

Whether the asset has a debug visualization implemented.

property num_instances: int#

Number of instances of the asset.

This is equal to the number of asset instances per environment multiplied by the number of environments.

set_debug_vis(debug_vis: bool) bool#

Sets whether to visualize the asset data.

Parameters:

debug_vis – Whether to visualize the asset data.

Returns:

Whether the debug visualization was successfully set. False if the asset does not support debug visualization.

write_root_state_to_sim(root_state: torch.Tensor, env_ids: Sequence[int] | None = None)#

Set the root state over selected environment indices into the simulation.

The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear and angular velocity. All the quantities are in the simulation frame.

Parameters:
  • root_state – Root state in simulation frame. Shape is (len(env_ids), 13).

  • env_ids – Environment indices. If None, then all indices are used.

class omni.isaac.orbit.assets.ArticulationData[source]#

Bases: RigidObjectData

Data container for an articulation.

Attributes:

joint_names

Joint names in the order parsed by the simulation view.

default_joint_pos

Default joint positions of all joints.

default_joint_vel

Default joint velocities of all joints.

joint_pos

Joint positions of all joints.

joint_vel

Joint velocities of all joints.

joint_acc

Joint acceleration of all joints.

joint_pos_target

Joint position targets commanded by the user.

joint_vel_target

Joint velocity targets commanded by the user.

joint_effort_target

Joint effort targets commanded by the user.

body_ang_acc_w

Angular acceleration of all bodies in simulation world frame.

body_ang_vel_w

Angular velocity of all bodies in simulation world frame.

body_lin_acc_w

Linear acceleration of all bodies in simulation world frame.

body_lin_vel_w

Linear velocity of all bodies in simulation world frame.

body_pos_w

Positions of all bodies in simulation world frame.

body_quat_w

Orientation (w, x, y, z) of all bodies in simulation world frame.

body_vel_w

Velocity of all bodies in simulation world frame.

root_ang_vel_b

Root angular velocity in base world frame.

root_ang_vel_w

Root angular velocity in simulation world frame.

root_lin_vel_b

Root linear velocity in base frame.

root_lin_vel_w

Root linear velocity in simulation world frame.

root_pos_w

Root position in simulation world frame.

root_quat_w

Root orientation (w, x, y, z) in simulation world frame.

root_vel_w

Root velocity in simulation world frame.

joint_stiffness

Joint stiffness provided to simulation.

joint_damping

Joint damping provided to simulation.

joint_armature

Joint armature provided to simulation.

joint_friction

Joint friction provided to simulation.

computed_torque

Joint torques computed from the actuator model (before clipping).

applied_torque

Joint torques applied from the actuator model (after clipping).

soft_joint_pos_limits

Joint positions limits for all joints.

soft_joint_vel_limits

Joint velocity limits for all joints.

gear_ratio

Gear ratio for relating motor torques to applied Joint torques.

joint_names: list[str] = None#

Joint names in the order parsed by the simulation view.

default_joint_pos: torch.Tensor = None#

Default joint positions of all joints. Shape is (num_instances, num_joints).

default_joint_vel: torch.Tensor = None#

Default joint velocities of all joints. Shape is (num_instances, num_joints).

joint_pos: torch.Tensor = None#

Joint positions of all joints. Shape is (num_instances, num_joints).

joint_vel: torch.Tensor = None#

Joint velocities of all joints. Shape is (num_instances, num_joints).

joint_acc: torch.Tensor = None#

Joint acceleration of all joints. Shape is (num_instances, num_joints).

joint_pos_target: torch.Tensor = None#

Joint position targets commanded by the user. Shape is (num_instances, num_joints).

For an implicit actuator model, the targets are directly set into the simulation. For an explicit actuator model, the targets are used to compute the joint torques (see applied_torque), which are then set into the simulation.

joint_vel_target: torch.Tensor = None#

Joint velocity targets commanded by the user. Shape is (num_instances, num_joints).

For an implicit actuator model, the targets are directly set into the simulation. For an explicit actuator model, the targets are used to compute the joint torques (see applied_torque), which are then set into the simulation.

joint_effort_target: torch.Tensor = None#

Joint effort targets commanded by the user. Shape is (num_instances, num_joints).

For an implicit actuator model, the targets are directly set into the simulation. For an explicit actuator model, the targets are used to compute the joint torques (see applied_torque), which are then set into the simulation.

body_acc_w: torch.Tensor = None#

Acceleration of all bodies. Shape is (num_instances, num_bodies, 6).

Note

This quantity is computed based on the rigid body state from the last step.

property body_ang_acc_w: torch.Tensor#

Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_ang_vel_w: torch.Tensor#

Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_lin_acc_w: torch.Tensor#

Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_lin_vel_w: torch.Tensor#

Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

body_names: list[str] = None#

Body names in the order parsed by the simulation view.

property body_pos_w: torch.Tensor#

Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).

property body_quat_w: torch.Tensor#

Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).

body_state_w: torch.Tensor = None#

State of all bodies [pos, quat, lin_vel, ang_vel] in simulation world frame. Shape is (num_instances, num_bodies, 13).

property body_vel_w: torch.Tensor#

Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).

default_root_state: torch.Tensor = None#

Default root state [pos, quat, lin_vel, ang_vel] in local environment frame. Shape is (num_instances, 13).

heading_w: torch.Tensor = None#

Yaw heading of the base frame (in radians). Shape is (num_instances,).

Note

This quantity is computed by assuming that the forward-direction of the base frame is along x-direction, i.e. \((1, 0, 0)\).

projected_gravity_b: torch.Tensor = None#

Projection of the gravity direction on base frame. Shape is (num_instances, 3).

property root_ang_vel_b: torch.Tensor#

Root angular velocity in base world frame. Shape is (num_instances, 3).

property root_ang_vel_w: torch.Tensor#

Root angular velocity in simulation world frame. Shape is (num_instances, 3).

property root_lin_vel_b: torch.Tensor#

Root linear velocity in base frame. Shape is (num_instances, 3).

property root_lin_vel_w: torch.Tensor#

Root linear velocity in simulation world frame. Shape is (num_instances, 3).

property root_pos_w: torch.Tensor#

Root position in simulation world frame. Shape is (num_instances, 3).

property root_quat_w: torch.Tensor#

Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4).

root_state_w: torch.Tensor = None#

Root state [pos, quat, lin_vel, ang_vel] in simulation world frame. Shape is (num_instances, 13).

root_vel_b: torch.Tensor = None#

Root velocity [lin_vel, ang_vel] in base frame. Shape is (num_instances, 6).

property root_vel_w: torch.Tensor#

Root velocity in simulation world frame. Shape is (num_instances, 6).

joint_stiffness: torch.Tensor = None#

Joint stiffness provided to simulation. Shape is (num_instances, num_joints).

joint_damping: torch.Tensor = None#

Joint damping provided to simulation. Shape is (num_instances, num_joints).

joint_armature: torch.Tensor = None#

Joint armature provided to simulation. Shape is (num_instances, num_joints).

joint_friction: torch.Tensor = None#

Joint friction provided to simulation. Shape is (num_instances, num_joints).

computed_torque: torch.Tensor = None#

Joint torques computed from the actuator model (before clipping). Shape is (num_instances, num_joints).

This quantity is the raw torque output from the actuator mode, before any clipping is applied. It is exposed for users who want to inspect the computations inside the actuator model. For instance, to penalize the learning agent for a difference between the computed and applied torques.

Note: The torques are zero for implicit actuator models.

applied_torque: torch.Tensor = None#

Joint torques applied from the actuator model (after clipping). Shape is (num_instances, num_joints).

These torques are set into the simulation, after clipping the computed_torque based on the actuator model.

Note: The torques are zero for implicit actuator models.

soft_joint_pos_limits: torch.Tensor = None#

Joint positions limits for all joints. Shape is (num_instances, num_joints, 2).

soft_joint_vel_limits: torch.Tensor = None#

Joint velocity limits for all joints. Shape is (num_instances, num_joints).

gear_ratio: torch.Tensor = None#

Gear ratio for relating motor torques to applied Joint torques. Shape is (num_instances, num_joints).

class omni.isaac.orbit.assets.ArticulationCfg[source]#

Bases: RigidObjectCfg

Configuration parameters for an articulation.

Classes:

InitialStateCfg

Initial state of the articulation.

Attributes:

init_state

Initial state of the articulated object.

soft_joint_pos_limit_factor

Fraction specifying the range of DOF position limits (parsed from the asset) to use.

actuators

Actuators for the robot with corresponding joint names.

class InitialStateCfg[source]#

Bases: InitialStateCfg

Initial state of the articulation.

Attributes:

joint_pos

Joint positions of the joints.

joint_vel

Joint velocities of the joints.

joint_pos: dict[str, float]#

Joint positions of the joints. Defaults to 0.0 for all joints.

joint_vel: dict[str, float]#

Joint velocities of the joints. Defaults to 0.0 for all joints.

pos: tuple[float, float, float]#

Position of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

rot: tuple[float, float, float, float]#

Quaternion rotation (w, x, y, z) of the root in simulation world frame. Defaults to (1.0, 0.0, 0.0, 0.0).

lin_vel: tuple[float, float, float]#

Linear velocity of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

ang_vel: tuple[float, float, float]#

Angular velocity of the root in simulation world frame. Defaults to (0.0, 0.0, 0.0).

prim_path: str#

Prim path (or expression) to the asset.

Note

The expression can contain the environment namespace regex {ENV_REGEX_NS} which will be replaced with the environment namespace.

Example: {ENV_REGEX_NS}/Robot will be replaced with /World/envs/env_.*/Robot.

spawn: SpawnerCfg | None#

Spawn configuration for the asset. Defaults to None.

If None, then no prims are spawned by the asset class. Instead, it is assumed that the asset is already present in the scene.

init_state: InitialStateCfg#

Initial state of the articulated object. Defaults to identity pose with zero velocity and zero joint state.

collision_group: Literal[0, -1]#

Collision group of the asset. Defaults to 0.

  • -1: global collision group (collides with all assets in the scene).

  • 0: local collision group (collides with other assets in the same environment).

debug_vis: bool#

Whether to enable debug visualization for the asset. Defaults to False.

soft_joint_pos_limit_factor: float#

Fraction specifying the range of DOF position limits (parsed from the asset) to use. Defaults to 1.0.

actuators: dict[str, omni.isaac.orbit.actuators.actuator_cfg.ActuatorBaseCfg]#

Actuators for the robot with corresponding joint names.