[isaacsim.sensors.experimental.physics] Isaac Sim Physics Sensor Simulation#

Version: 2.2.0

Isaac Sim Physics Sensor Simulation extension provides APIs for physics-based sensors, including Contact Sensor, Effort Sensor, & IMU Sensor.

Preview

Enable Extension#

The extension can be enabled (if not already) in one of the following ways:

Define the next entry as an application argument from a terminal.

APP_SCRIPT.(sh|bat) --enable isaacsim.sensors.experimental.physics

Define the next entry under [dependencies] in an experience (.kit) file or an extension configuration (extension.toml) file.

[dependencies]
"isaacsim.sensors.experimental.physics" = {}

Open the Window > Extensions menu in a running application instance and search for isaacsim.sensors.experimental.physics. Then, toggle the enable control button if it is not already active.

API#

Python API#

Commands

IsaacSensorExperimentalCreatePrim

Base command for creating Isaac Sensor prims.

IsaacSensorExperimentalCreateContactSensor

Command for creating a contact sensor prim.

IsaacSensorExperimentalCreateImuSensor

Command for creating an IMU sensor prim.

Sensors

ContactSensor

High-level contact sensor wrapper with frame-based data access.

EffortSensorReading

Effort sensor reading data.

EffortSensor

Sensor for measuring joint effort (torque/force).

IMUSensor

High-level IMU sensor wrapper with frame-based data access.


Commands#

class IsaacSensorExperimentalCreatePrim(*args: Any, **kwargs: Any)#

Bases: Command

Base command for creating Isaac Sensor prims.

Creates a sensor prim at the specified path with the given schema type and transform. This is a base command used by specific sensor creation commands.

Parameters:
  • path – Relative path for the new prim (appended to parent).

  • parent – Parent prim path. If empty, path is used as absolute.

  • translation – Local translation offset.

  • orientation – Local orientation as quaternion [w, x, y, z].

  • schema_type – USD schema type for the sensor prim.

class IsaacSensorExperimentalCreateContactSensor(*args: Any, **kwargs: Any)#

Bases: Command

Command for creating a contact sensor prim.

Creates an IsaacContactSensor prim under the specified parent with configurable threshold, radius, and color. Also applies the PhysxContactReportAPI to the parent prim to enable contact reporting.

Parameters:
  • path – Relative path for the sensor (appended to parent).

  • parent – Parent prim path. Must have a collision-enabled prim.

  • min_threshold – Minimum force threshold in Newtons.

  • max_threshold – Maximum force threshold in Newtons.

  • color – Visualization color as [r, g, b, a].

  • radius – Contact detection radius. Negative disables radius filtering.

  • translation – Local translation offset.

class IsaacSensorExperimentalCreateImuSensor(*args: Any, **kwargs: Any)#

Bases: Command

Command for creating an IMU sensor prim.

Creates an IsaacImuSensor prim under the specified parent with configurable filter widths.

Parameters:
  • path – Relative path for the sensor (appended to parent).

  • parent – Parent prim path.

  • translation – Local translation offset.

  • orientation – Local orientation as quaternion [w, x, y, z].

  • linear_acceleration_filter_size – Rolling average window for acceleration.

  • angular_velocity_filter_size – Rolling average window for angular velocity.

  • orientation_filter_size – Rolling average window for orientation.


Sensors#

class ContactSensor(
prim_path: str,
name: str | None = 'contact_sensor',
translation: ndarray | None = None,
position: ndarray | None = None,
min_threshold: float | None = None,
max_threshold: float | None = None,
radius: float | None = None,
)#

Bases: XformPrim

High-level contact sensor wrapper with frame-based data access.

Provides a convenient interface for contact sensing including automatic sensor creation if the prim doesn’t exist, configurable thresholds and radius, and structured frame data output.

Parameters:
  • prim_path – USD path where the sensor should be located.

  • name – Human-readable name for the sensor.

  • translation – Local translation offset from parent. Cannot be used with position.

  • position – World position. Cannot be used with translation.

  • min_threshold – Minimum force threshold in Newtons.

  • max_threshold – Maximum force threshold in Newtons.

  • radius – Contact detection radius. Negative means no radius filtering.

Raises:
  • ValueError – If both position and translation are specified.

  • ValueError – If parent prim doesn’t have CollisionAPI.

  • RuntimeError – If sensor creation fails.

Example:

from isaacsim.sensors.experimental.physics import ContactSensor

# Create sensor on existing prim
sensor = ContactSensor("/World/Robot/foot/contact_sensor")

# Or create new sensor with custom parameters
sensor = ContactSensor(
    "/World/Robot/foot/contact_sensor",
    min_threshold=1.0,
    max_threshold=1000.0,
    radius=0.05
)

# Get current contact data
frame = sensor.get_current_frame()
if frame["in_contact"]:
    print(f"Contact force: {frame['force']}")
add_raw_contact_data_to_frame()#

Enable raw contact data in frame output.

After calling this, get_current_frame() will include a “contacts” list with detailed per-contact information.

Example:

>>> sensor.add_raw_contact_data_to_frame()
apply_visual_materials(
materials: type['VisualMaterial'] | list[type['VisualMaterial']],
*,
weaker_than_descendants: bool | list | np.ndarray | wp.array | None = None,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Apply visual materials to the prims, and optionally, to their descendants.

Backends: usd.

Parameters:
  • visual_materials – Visual materials to be applied to the prims (shape (N,)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • weaker_than_descendants – Boolean flags to indicate whether descendant materials should be overridden (shape (N, 1)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> from isaacsim.core.experimental.materials import OmniGlassMaterial
>>>
>>> # create a dark-red glass visual material
>>> material = OmniGlassMaterial("/World/material/glass")
>>> material.set_input_values("glass_ior", [1.25])
>>> material.set_input_values("depth", [0.001])
>>> material.set_input_values("thin_walled", [False])
>>> material.set_input_values("glass_color", [0.5, 0.0, 0.0])
>>>
>>> prims.apply_visual_materials(material)
static ensure_api(
prims: list[Usd.Prim],
api: type,
*args,
**kwargs,
) list[type['UsdAPISchemaBase']]#

Ensure that all prims have the specified API schema applied.

Backends: usd.

If a prim doesn’t have the API schema, it will be applied. If it already has it, the existing API schema will be returned.

Parameters:
  • prims – List of USD Prims to ensure API schema on.

  • api – The API schema type to ensure.

  • *args – Additional positional arguments passed to API schema when applying it.

  • **kwargs – Additional keyword arguments passed to API schema when applying it.

Returns:

List of API schema objects, one for each input prim.

Example:

>>> import isaacsim.core.experimental.utils.prim as prim_utils
>>> from pxr import UsdPhysics
>>> from isaacsim.core.experimental.prims import Prim
>>>
>>> # given a USD stage with 3 prims at paths /World/prim_0, /World/prim_1, /World/prim_2,
>>> # ensure all prims have physics API schema
>>> usd_prims = [prim_utils.get_prim_at_path(f"/World/prim_{i}") for i in range(3)]
>>> physics_apis = Prim.ensure_api(usd_prims, UsdPhysics.RigidBodyAPI)
get_applied_visual_materials(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) list[type['VisualMaterial'] | None]#

Get the applied visual materials.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

List of applied visual materials (shape (N,)). If a prim does not have a material, None is returned.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the applied visual material of the last wrapped prim
>>> prims.get_applied_visual_materials(indices=[2])[0]
<isaacsim.core.experimental.materials.impl.visual_materials.omni_glass.OmniGlassMaterial object at 0x...>
get_current_frame() dict#

Get the current contact sensor data as a structured frame.

Returns:

  • “in_contact”: Whether contact is detected.

  • ”force”: Contact force magnitude.

  • ”time”: Simulation time of reading.

  • ”physics_step”: Physics step number.

  • ”number_of_contacts”: Number of contact points.

  • ”contacts”: Raw contact data if enabled via add_raw_contact_data_to_frame.

Return type:

Frame data containing

Example:

>>> frame = sensor.get_current_frame()  
>>> frame["in_contact"]  
False
get_default_state(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array | None, wp.array | None]#

Get the default state (positions and orientations) of the prims.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The default positions in the world frame (shape (N, 3)). 2) The default orientations in the world frame (shape (N, 4), quaternion wxyz). If the default state is not set using the set_default_state() method, None is returned.

Raises:
  • AssertionError – Wrapped prims are not valid.

  • AssertionError – If prims are non-root articulation links.

get_local_poses(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array, wp.array]#

Get the poses (translations and orientations) in the local frame of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The translations in the local frame (shape (N, 3)). 2) The orientations in the local frame (shape (N, 4), quaternion wxyz).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the local poses of all prims
>>> translations, orientations = prims.get_local_poses()
>>> translations.shape, orientations.shape
((3, 3), (3, 4))
>>>
>>> # get the local pose of the first prim
>>> translations, orientations = prims.get_local_poses(indices=[0])
>>> translations.shape, orientations.shape
((1, 3), (1, 4))
get_local_scales(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) wp.array#

Get the local scales of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Scales of the prims (shape (N, 3)).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get local scales of all prims
>>> scales = prims.get_local_scales()
>>> scales.shape
(3, 3)
get_max_threshold() float | None#

Maximum force threshold in Newtons.

Returns:

Maximum threshold in Newtons, or None if not set.

Example:

>>> sensor.get_max_threshold()  
100000.0
get_min_threshold() float | None#

Minimum force threshold in Newtons.

Returns:

Minimum threshold in Newtons, or None if not set.

Example:

>>> sensor.get_min_threshold()  
0.0
get_radius() float#

Get the contact detection radius.

Returns:

Radius in stage units. Negative means no radius filtering.

Example:

>>> sensor.get_radius()  
-1.0
get_visibilities(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) wp.array#

Get the visibility state (whether prims are visible or invisible during rendering) of the prims.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Boolean flags indicating the visibility state (shape (N, 1)).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the visibility states of all prims
>>> visibilities = prims.get_visibilities()
>>> print(visibilities)
[[ True] [ True] [ True]]
>>>
>>> # get the visibility states of the first and last prims
>>> visibilities = prims.get_visibilities(indices=[0, 2])
>>> print(visibilities)
[[ True] [ True]]
get_world_poses(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array, wp.array]#

Get the poses (positions and orientations) in the world frame of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The positions in the world frame (shape (N, 3)). 2) The orientations in the world frame (shape (N, 4), quaternion wxyz).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the world poses of all prims
>>> positions, orientations = prims.get_world_poses()
>>> positions.shape, orientations.shape
((3, 3), (3, 4))
>>>
>>> # get the world pose of the first prim
>>> positions, orientations = prims.get_world_poses(indices=[0])
>>> positions.shape, orientations.shape
((1, 3), (1, 4))
initialize(physics_sim_view: Any = None)#

Initialize the sensor for simulation.

This method is provided for API compatibility and currently performs no action as initialization happens automatically.

Parameters:

physics_sim_view – Unused. Provided for API compatibility.

remove_raw_contact_data_from_frame()#

Disable raw contact data in frame output.

Removes the “contacts” key from frame output to reduce overhead.

Example:

>>> sensor.remove_raw_contact_data_from_frame()
reset_to_default_state(
*,
warn_on_non_default_state: bool = False,
) None#

Reset the prims to the specified default state.

Backends: usd, usdrt, fabric.

This method applies the default state defined using the set_default_state() method.

Note

This method teleports prims to the specified default state (positions and orientations).

Warning

This method has no effect on non-root articulation links or when no default state is set. In this case, a warning message is logged if warn_on_non_default_state is True.

Parameters:

warn_on_non_default_state – Whether to log a warning message when no default state is set.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get default state (no default state set at this point)
>>> prims.get_default_state()
(None, None)
>>>
>>> # set default state
>>> # - random positions for each prim
>>> # - same fixed orientation for all prim
>>> positions = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> prims.set_default_state(positions, orientations=[1.0, 0.0, 0.0, 0.0])
>>>
>>> # get default state (default state is set)
>>> prims.get_default_state()
(array(shape=(3, 3), dtype=float32), array(shape=(3, 4), dtype=float32))
>>>
>>> # reset prims to default state
>>> prims.reset_to_default_state()
reset_xform_op_properties() None#

Reset the transformation operation attributes of the prims to a standard set.

Backends: usd.

It ensures that each prim has only the following transformations in the specified order. Any other transformation operations are removed, so they are not consumed.

  1. xformOp:translate (double precision)

  2. xformOp:orient (double precision)

  3. xformOp:scale (double precision)

Note

This method preserves the poses of the prims in the world frame while reorganizing the transformation operations.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # reset transform operations of all prims
>>> prims.reset_xform_op_properties()
>>>
>>> # verify transform operations of the first wrapped prim
>>> prims.prims[0].GetPropertyNames()
[... 'xformOp:orient', 'xformOp:scale', 'xformOp:translate', 'xformOpOrder']
static resolve_paths(
paths: str | list[str],
raise_on_mixed_paths: bool = True,
) tuple[list[str], list[str]]#

Resolve paths to prims in the stage to get existing and non-existing paths.

Backends: usd.

Parameters:
  • paths – Single path or list of paths to USD prims. Paths may contain regular expressions to match multiple prims.

  • raise_on_mixed_paths – Whether to raise an error if resulting paths are mixed or invalid.

Returns:

Two-elements tuple. 1) List of existing paths. 2) List of non-existing paths.

Raises:

ValueError – If resulting paths are mixed or invalid and raise_on_mixed_paths is True.

set_default_state(
positions: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the default state (positions and orientations) of the prims.

Backends: usd.

Hint

Prims can be reset to their default state by calling the reset_to_default_state() method.

Parameters:
  • positions – Default positions in the world frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Default orientations in the world frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither positions nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

  • AssertionError – If prims are non-root articulation links.

set_local_poses(
translations: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the poses (translations and orientations) in the local frame of the prims.

Backends: usd, usdrt, fabric.

Note

This method teleports prims to the specified poses.

Parameters:
  • translations – Translations in the local frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Orientations in the local frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither translations nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

Example:

>>> # set random poses for all prims
>>> translations = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> orientations = np.random.randn(3, 4)
>>> orientations = orientations / np.linalg.norm(orientations, axis=-1, keepdims=True)  # normalize quaternions
>>> prims.set_local_poses(translations, orientations)
set_local_scales(
scales: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the local scales of the prims.

Backends: usd, usdrt, fabric.

Parameters:
  • scales – Scales to be applied to the prims (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # set random positive scales for all prims
>>> scales = np.random.uniform(low=0.5, high=1.5, size=(3, 3))
>>> prims.set_local_scales(scales)
set_max_threshold(value: float)#

Set the maximum force threshold.

Contact forces are clamped to this maximum value.

Parameters:

value – Threshold in Newtons.

Example:

>>> sensor.set_max_threshold(2000.0)
set_min_threshold(value: float)#

Set the minimum force threshold.

Contacts with force below this threshold are ignored.

Parameters:

value – Threshold in Newtons.

Example:

>>> sensor.set_min_threshold(0.5)
set_radius(value: float)#

Set the contact detection radius.

Parameters:

value – Radius in stage units. Use negative to disable radius filtering.

Example:

>>> sensor.set_radius(0.1)
set_visibilities(
visibilities: bool | list | np.ndarray | wp.array,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the visibility state (whether prims are visible or invisible during rendering) of the prims.

Backends: usd.

Parameters:
  • visibilities – Boolean flags to set the visibility state (shape (N, 1)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # make all prims invisible
>>> prims.set_visibilities([False])
>>>
>>> # make first and last prims invisible
>>> prims.set_visibilities([True])  # restore visibility from previous call
>>> prims.set_visibilities([False], indices=[0, 2])
set_world_poses(
positions: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the poses (positions and orientations) in the world frame of the prims.

Backends: usd, usdrt, fabric.

Note

This method teleports prims to the specified poses.

Parameters:
  • positions – Positions in the world frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Orientations in the world frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither positions nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

Example:

>>> # set random poses for all prims
>>> positions = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> orientations = np.random.randn(3, 4)
>>> orientations = orientations / np.linalg.norm(orientations, axis=-1, keepdims=True)  # normalize quaternions
>>> prims.set_world_poses(positions, orientations)

Indicate if the wrapped prims are a non-root link in an articulation tree.

Backends: usd.

Warning

Transformation of the poses of non-root links in an articulation tree are not supported.

Returns:

Whether the prims are a non-root link in an articulation tree.

property paths: list[str]#

Prim paths in the stage encapsulated by the wrapper.

Returns:

List of prim paths as strings.

Example:

>>> prims.paths
['/World/prim_0', '/World/prim_1', '/World/prim_2']
property prim_path: str#

Get the USD path of this sensor.

Returns:

USD path string.

property prims: list[pxr.Usd.Prim]#

USD Prim objects encapsulated by the wrapper.

Returns:

List of USD Prim objects.

Example:

>>> prims.prims
[Usd.Prim(</World/prim_0>), Usd.Prim(</World/prim_1>), Usd.Prim(</World/prim_2>)]
property valid: bool#

Whether all prims in the wrapper are valid.

Returns:

True if all prim paths specified in the wrapper correspond to valid prims in stage, False otherwise.

Example:

>>> prims.valid
True
class EffortSensorReading(
is_valid: bool = False,
time: float = 0,
value: float = 0,
)#

Bases: object

Effort sensor reading data.

Parameters:
  • is_valid – Whether this reading contains valid data.

  • time – Simulation time when the reading was taken.

  • value – Effort (torque/force) value at the joint.

class EffortSensor(prim_path: str, enabled: bool = True)#

Bases: object

Sensor for measuring joint effort (torque/force).

Reads effort values from an articulated body’s joint via the C++ IEffortSensor plugin. Maintains a Python-side circular buffer of readings for historical access.

Parameters:
  • prim_path – USD path to the joint, formatted as articulation_path/joint_name.

  • enabled – Whether the sensor is initially enabled.

Example

from isaacsim.sensors.experimental.physics import EffortSensor

# Create sensor for a robot joint
sensor = EffortSensor("/World/Robot/joint_1")

# Read joint effort
reading = sensor.get_sensor_reading()
if reading.is_valid:
    print(f"Joint torque: {reading.value}")
change_buffer_size(new_buffer_size: int)#

Change the size of the sensor reading buffer.

Parameters:

new_buffer_size – New buffer size (number of readings to store).

Example:

>>> sensor.change_buffer_size(4)
get_sensor_reading() EffortSensorReading#

Get the current effort sensor reading.

Returns:

Reading with effort value and validity state.

Example:

>>> reading = sensor.get_sensor_reading()  
>>> reading.is_valid  
False
update_dof_name(dof_name: str)#

Update the DOF (degree of freedom) name being measured.

Creates a new backend targeting the updated joint path.

Parameters:

dof_name – Name of the joint DOF to monitor.

Example:

>>> sensor.update_dof_name("joint_1")
class IMUSensor(
prim_path: str,
name: str | None = 'imu_sensor',
translation: ndarray | None = None,
position: ndarray | None = None,
orientation: ndarray | None = None,
linear_acceleration_filter_size: int | None = 1,
angular_velocity_filter_size: int | None = 1,
orientation_filter_size: int | None = 1,
)#

Bases: XformPrim

High-level IMU sensor wrapper with frame-based data access.

Provides a convenient interface for IMU sensing including automatic sensor creation if the prim doesn’t exist, configurable filter widths, and structured frame data output.

Parameters:
  • prim_path – USD path where the sensor should be located.

  • name – Human-readable name for the sensor.

  • translation – Local translation offset from parent. Cannot be used with position.

  • position – World position. Cannot be used with translation.

  • orientation – Sensor orientation as [w, x, y, z] quaternion.

  • linear_acceleration_filter_size – Rolling average window for acceleration.

  • angular_velocity_filter_size – Rolling average window for angular velocity.

  • orientation_filter_size – Rolling average window for orientation.

Raises:
  • ValueError – If both position and translation are specified.

  • RuntimeError – If sensor creation fails.

Example

from isaacsim.sensors.experimental.physics import IMUSensor

# Create sensor on existing prim
sensor = IMUSensor("/World/Robot/body/imu")

# Or create new sensor with custom parameters
sensor = IMUSensor(
    "/World/Robot/body/imu",
    linear_acceleration_filter_size=5
)

# Get current IMU data
frame = sensor.get_current_frame()
print(f"Linear acceleration: {frame['linear_acceleration']}")
print(f"Angular velocity: {frame['angular_velocity']}")
print(f"Orientation: {frame['orientation']}")
apply_visual_materials(
materials: type['VisualMaterial'] | list[type['VisualMaterial']],
*,
weaker_than_descendants: bool | list | np.ndarray | wp.array | None = None,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Apply visual materials to the prims, and optionally, to their descendants.

Backends: usd.

Parameters:
  • visual_materials – Visual materials to be applied to the prims (shape (N,)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • weaker_than_descendants – Boolean flags to indicate whether descendant materials should be overridden (shape (N, 1)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> from isaacsim.core.experimental.materials import OmniGlassMaterial
>>>
>>> # create a dark-red glass visual material
>>> material = OmniGlassMaterial("/World/material/glass")
>>> material.set_input_values("glass_ior", [1.25])
>>> material.set_input_values("depth", [0.001])
>>> material.set_input_values("thin_walled", [False])
>>> material.set_input_values("glass_color", [0.5, 0.0, 0.0])
>>>
>>> prims.apply_visual_materials(material)
static ensure_api(
prims: list[Usd.Prim],
api: type,
*args,
**kwargs,
) list[type['UsdAPISchemaBase']]#

Ensure that all prims have the specified API schema applied.

Backends: usd.

If a prim doesn’t have the API schema, it will be applied. If it already has it, the existing API schema will be returned.

Parameters:
  • prims – List of USD Prims to ensure API schema on.

  • api – The API schema type to ensure.

  • *args – Additional positional arguments passed to API schema when applying it.

  • **kwargs – Additional keyword arguments passed to API schema when applying it.

Returns:

List of API schema objects, one for each input prim.

Example:

>>> import isaacsim.core.experimental.utils.prim as prim_utils
>>> from pxr import UsdPhysics
>>> from isaacsim.core.experimental.prims import Prim
>>>
>>> # given a USD stage with 3 prims at paths /World/prim_0, /World/prim_1, /World/prim_2,
>>> # ensure all prims have physics API schema
>>> usd_prims = [prim_utils.get_prim_at_path(f"/World/prim_{i}") for i in range(3)]
>>> physics_apis = Prim.ensure_api(usd_prims, UsdPhysics.RigidBodyAPI)
get_applied_visual_materials(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) list[type['VisualMaterial'] | None]#

Get the applied visual materials.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

List of applied visual materials (shape (N,)). If a prim does not have a material, None is returned.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the applied visual material of the last wrapped prim
>>> prims.get_applied_visual_materials(indices=[2])[0]
<isaacsim.core.experimental.materials.impl.visual_materials.omni_glass.OmniGlassMaterial object at 0x...>
get_current_frame(read_gravity: bool = True) dict#

Get the current IMU sensor data as a structured frame.

Parameters:

read_gravity – If True, include gravity in acceleration readings.

Returns:

  • “linear_acceleration”: Linear acceleration [x, y, z].

  • ”angular_velocity”: Angular velocity [x, y, z].

  • ”orientation”: Orientation as [w, x, y, z] quaternion.

  • ”time”: Simulation time of reading.

  • ”physics_step”: Physics step number.

Return type:

Frame data containing

Example:

>>> frame = sensor.get_current_frame()  
>>> frame["orientation"]  
array([1., 0., 0., 0.], dtype=float32)
get_default_state(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array | None, wp.array | None]#

Get the default state (positions and orientations) of the prims.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The default positions in the world frame (shape (N, 3)). 2) The default orientations in the world frame (shape (N, 4), quaternion wxyz). If the default state is not set using the set_default_state() method, None is returned.

Raises:
  • AssertionError – Wrapped prims are not valid.

  • AssertionError – If prims are non-root articulation links.

get_local_poses(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array, wp.array]#

Get the poses (translations and orientations) in the local frame of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The translations in the local frame (shape (N, 3)). 2) The orientations in the local frame (shape (N, 4), quaternion wxyz).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the local poses of all prims
>>> translations, orientations = prims.get_local_poses()
>>> translations.shape, orientations.shape
((3, 3), (3, 4))
>>>
>>> # get the local pose of the first prim
>>> translations, orientations = prims.get_local_poses(indices=[0])
>>> translations.shape, orientations.shape
((1, 3), (1, 4))
get_local_scales(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) wp.array#

Get the local scales of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Scales of the prims (shape (N, 3)).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get local scales of all prims
>>> scales = prims.get_local_scales()
>>> scales.shape
(3, 3)
get_visibilities(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) wp.array#

Get the visibility state (whether prims are visible or invisible during rendering) of the prims.

Backends: usd.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Boolean flags indicating the visibility state (shape (N, 1)).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the visibility states of all prims
>>> visibilities = prims.get_visibilities()
>>> print(visibilities)
[[ True] [ True] [ True]]
>>>
>>> # get the visibility states of the first and last prims
>>> visibilities = prims.get_visibilities(indices=[0, 2])
>>> print(visibilities)
[[ True] [ True]]
get_world_poses(
*,
indices: int | list | np.ndarray | wp.array | None = None,
) tuple[wp.array, wp.array]#

Get the poses (positions and orientations) in the world frame of the prims.

Backends: usd, usdrt, fabric.

Parameters:

indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Returns:

Two-elements tuple. 1) The positions in the world frame (shape (N, 3)). 2) The orientations in the world frame (shape (N, 4), quaternion wxyz).

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get the world poses of all prims
>>> positions, orientations = prims.get_world_poses()
>>> positions.shape, orientations.shape
((3, 3), (3, 4))
>>>
>>> # get the world pose of the first prim
>>> positions, orientations = prims.get_world_poses(indices=[0])
>>> positions.shape, orientations.shape
((1, 3), (1, 4))
initialize(physics_sim_view: Any = None)#

Initialize the sensor for simulation.

This method is provided for API compatibility and currently performs no action as initialization happens automatically.

Parameters:

physics_sim_view – Unused. Provided for API compatibility.

reset_to_default_state(
*,
warn_on_non_default_state: bool = False,
) None#

Reset the prims to the specified default state.

Backends: usd, usdrt, fabric.

This method applies the default state defined using the set_default_state() method.

Note

This method teleports prims to the specified default state (positions and orientations).

Warning

This method has no effect on non-root articulation links or when no default state is set. In this case, a warning message is logged if warn_on_non_default_state is True.

Parameters:

warn_on_non_default_state – Whether to log a warning message when no default state is set.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # get default state (no default state set at this point)
>>> prims.get_default_state()
(None, None)
>>>
>>> # set default state
>>> # - random positions for each prim
>>> # - same fixed orientation for all prim
>>> positions = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> prims.set_default_state(positions, orientations=[1.0, 0.0, 0.0, 0.0])
>>>
>>> # get default state (default state is set)
>>> prims.get_default_state()
(array(shape=(3, 3), dtype=float32), array(shape=(3, 4), dtype=float32))
>>>
>>> # reset prims to default state
>>> prims.reset_to_default_state()
reset_xform_op_properties() None#

Reset the transformation operation attributes of the prims to a standard set.

Backends: usd.

It ensures that each prim has only the following transformations in the specified order. Any other transformation operations are removed, so they are not consumed.

  1. xformOp:translate (double precision)

  2. xformOp:orient (double precision)

  3. xformOp:scale (double precision)

Note

This method preserves the poses of the prims in the world frame while reorganizing the transformation operations.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # reset transform operations of all prims
>>> prims.reset_xform_op_properties()
>>>
>>> # verify transform operations of the first wrapped prim
>>> prims.prims[0].GetPropertyNames()
[... 'xformOp:orient', 'xformOp:scale', 'xformOp:translate', 'xformOpOrder']
static resolve_paths(
paths: str | list[str],
raise_on_mixed_paths: bool = True,
) tuple[list[str], list[str]]#

Resolve paths to prims in the stage to get existing and non-existing paths.

Backends: usd.

Parameters:
  • paths – Single path or list of paths to USD prims. Paths may contain regular expressions to match multiple prims.

  • raise_on_mixed_paths – Whether to raise an error if resulting paths are mixed or invalid.

Returns:

Two-elements tuple. 1) List of existing paths. 2) List of non-existing paths.

Raises:

ValueError – If resulting paths are mixed or invalid and raise_on_mixed_paths is True.

set_default_state(
positions: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the default state (positions and orientations) of the prims.

Backends: usd.

Hint

Prims can be reset to their default state by calling the reset_to_default_state() method.

Parameters:
  • positions – Default positions in the world frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Default orientations in the world frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither positions nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

  • AssertionError – If prims are non-root articulation links.

set_local_poses(
translations: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the poses (translations and orientations) in the local frame of the prims.

Backends: usd, usdrt, fabric.

Note

This method teleports prims to the specified poses.

Parameters:
  • translations – Translations in the local frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Orientations in the local frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither translations nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

Example:

>>> # set random poses for all prims
>>> translations = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> orientations = np.random.randn(3, 4)
>>> orientations = orientations / np.linalg.norm(orientations, axis=-1, keepdims=True)  # normalize quaternions
>>> prims.set_local_poses(translations, orientations)
set_local_scales(
scales: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the local scales of the prims.

Backends: usd, usdrt, fabric.

Parameters:
  • scales – Scales to be applied to the prims (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # set random positive scales for all prims
>>> scales = np.random.uniform(low=0.5, high=1.5, size=(3, 3))
>>> prims.set_local_scales(scales)
set_visibilities(
visibilities: bool | list | np.ndarray | wp.array,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the visibility state (whether prims are visible or invisible during rendering) of the prims.

Backends: usd.

Parameters:
  • visibilities – Boolean flags to set the visibility state (shape (N, 1)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:

AssertionError – Wrapped prims are not valid.

Example:

>>> # make all prims invisible
>>> prims.set_visibilities([False])
>>>
>>> # make first and last prims invisible
>>> prims.set_visibilities([True])  # restore visibility from previous call
>>> prims.set_visibilities([False], indices=[0, 2])
set_world_poses(
positions: list | np.ndarray | wp.array | None = None,
orientations: list | np.ndarray | wp.array | None = None,
*,
indices: int | list | np.ndarray | wp.array | None = None,
) None#

Set the poses (positions and orientations) in the world frame of the prims.

Backends: usd, usdrt, fabric.

Note

This method teleports prims to the specified poses.

Parameters:
  • positions – Positions in the world frame (shape (N, 3)). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • orientations – Orientations in the world frame (shape (N, 4), quaternion wxyz). If the input shape is smaller than expected, data will be broadcasted (following NumPy broadcast rules).

  • indices – Indices of prims to process (shape (N,)). If not defined, all wrapped prims are processed.

Raises:
  • AssertionError – If neither positions nor orientations are specified.

  • AssertionError – Wrapped prims are not valid.

Example:

>>> # set random poses for all prims
>>> positions = np.random.uniform(low=-1, high=1, size=(3, 3))
>>> orientations = np.random.randn(3, 4)
>>> orientations = orientations / np.linalg.norm(orientations, axis=-1, keepdims=True)  # normalize quaternions
>>> prims.set_world_poses(positions, orientations)

Indicate if the wrapped prims are a non-root link in an articulation tree.

Backends: usd.

Warning

Transformation of the poses of non-root links in an articulation tree are not supported.

Returns:

Whether the prims are a non-root link in an articulation tree.

property paths: list[str]#

Prim paths in the stage encapsulated by the wrapper.

Returns:

List of prim paths as strings.

Example:

>>> prims.paths
['/World/prim_0', '/World/prim_1', '/World/prim_2']
property prim_path: str#

Get the USD path of this sensor.

Returns:

USD path string.

property prims: list[pxr.Usd.Prim]#

USD Prim objects encapsulated by the wrapper.

Returns:

List of USD Prim objects.

Example:

>>> prims.prims
[Usd.Prim(</World/prim_0>), Usd.Prim(</World/prim_1>), Usd.Prim(</World/prim_2>)]
property valid: bool#

Whether all prims in the wrapper are valid.

Returns:

True if all prim paths specified in the wrapper correspond to valid prims in stage, False otherwise.

Example:

>>> prims.valid
True