[isaacsim.sensors.experimental.rtx] Isaac Sim RTX Sensor Simulation#
Version: 1.4.3
Overview#
The isaacsim.sensors.experimental.rtx extension provides experimental Python APIs for RTX-based sensor simulation in Isaac Sim, covering lidar, radar, acoustic (ultrasonic), and camera sensors. Each sensor type is split into an authoring class for USD prim creation and configuration, and a runtime sensor class for attaching annotators and retrieving data at simulation time.
Key Components#
Runtime sensor classes#
Runtime sensor classes wrap an authoring object, create a Replicator render product, and manage annotator attachment and data retrieval.
RTX sensors (lidar, radar, acoustic) support generic-model-output and stable-id-map annotators:
LidarSensor— Wraps aLidarobject (or creates one from a path).RadarSensor— Wraps aRadarobject (or creates one from a path).AcousticSensor— Wraps anAcousticobject (or creates one from a path).
Camera sensors support standard rendering annotators (RGB, depth, normals, segmentation, bounding boxes, etc.):
CameraSensor— Wraps aRtxCameraobject. Requires aresolutionparameter ((height, width)).TiledCameraSensor— Batched rendering of multiple cameras into a single tiled texture. Supports both tiled and per-camera batched output.SingleViewDepthCameraSensor— ExtendsCameraSensorwith stereoscopic depth simulation viaOmniSensorDepthSensorSingleViewAPI.
Lidar configuration registry#
Supported USD lidar assets and variants. The package exports SUPPORTED_LIDAR_CONFIGS (paths to known Isaac Sim lidar assets mapped to optional variant names) and SUPPORTED_LIDAR_VARIANT_SET_NAME (expected variant set name on those prims).
Parser utilities#
parse_generic_model_output_data— Decodesgeneric-model-outputannotator data into aGenericModelOutputstructure provided by the bundledisaacsim.sensors.experimental.rtx.generic_model_outputmodule.parse_stable_id_map_data— Decodesstable-id-mapdata into a mapping from stable object IDs to prim paths.parse_object_ids— Extracts 128-bit object IDs from aGenericModelOutput.objIdbuffer as Python ints matching the keys fromparse_stable_id_map_data.draw_annotator_data_to_image— Converts camera annotator data to BGR NumPy arrays for visualization.
Auxiliary modules#
The extension ships isaacsim.sensors.experimental.rtx.generic_model_output and isaacsim.sensors.experimental.rtx.sensor_checker alongside the main package. The former defines the binary layout used by parse_generic_model_output_data; the latter provides helpers such as SensorCheckerUtil and ModelInfo for working with supported sensor assets (see extension tests for typical usage).
Settings#
Kit settings contributed by this extension. Defaults and inline comments live in config/extension.toml under [settings]. The keys cover GPU-resident lidar and radar return buffers (app.sensors.nv.lidar.outputBufferOnGPU, app.sensors.nv.radar.outputBufferOnGPU), optional non-visual material semantics from USD (rtx.materialDb.nonVisualMaterialCSV.enabled, rtx.materialDb.nonVisualMaterialSemantics.prefix), and Hydra timeline use for RTX sensor models (rtx.rtxsensor.useHydraTimeAlways).
Code examples#
Lidar#
from isaacsim.sensors.experimental.rtx import Lidar, LidarSensor, parse_generic_model_output_data
import isaacsim.core.experimental.utils.app as app_utils
# authoring: create a lidar prim from a known config
lidar = Lidar.create(path="/World/lidar", config="OS1", variant="OS1_REV6_32ch20hz512res",
aux_output_level="FULL")
# runtime: attach annotators and retrieve data
sensor = LidarSensor(lidar, annotators=["generic-model-output"])
app_utils.play(commit=True)
data, _ = sensor.get_data("generic-model-output")
gmo = parse_generic_model_output_data(data)
Radar#
from isaacsim.sensors.experimental.rtx import Radar, RadarSensor
radar = Radar("/World/radar", tick_rate=20.0, aux_output_level="BASIC")
sensor = RadarSensor(radar, annotators=["generic-model-output"])
Acoustic#
from isaacsim.sensors.experimental.rtx import Acoustic, AcousticSensor
acoustic = Acoustic(
"/World/acoustic",
tick_rate=30.0,
aux_output_level="BASIC",
attributes={
"omni:sensor:WpmAcoustic:centerFrequency": 51200.0,
"omni:sensor:WpmAcoustic:sensorMount:m001:position": (0.0, 0.0, 0.0),
},
)
sensor = AcousticSensor(acoustic, annotators=["generic-model-output"])
Camera#
from isaacsim.sensors.experimental.rtx import RtxCamera, CameraSensor
cam = RtxCamera("/World/cam", tick_rate=30.0)
cam.camera.set_focal_lengths(24.0)
cam.camera.set_clipping_ranges(0.01, 1000.0)
sensor = CameraSensor(cam, resolution=(480, 640), annotators=["rgb", "distance_to_image_plane"])
Camera with lens distortion#
from isaacsim.sensors.experimental.rtx import RtxCamera, CameraSensor
from pxr import Gf
cam = RtxCamera(
"/World/cam",
schemas=["OmniLensDistortionOpenCvFisheyeAPI"],
attributes={
"omni:lensdistortion:opencvFisheye:fx": 500.0,
"omni:lensdistortion:opencvFisheye:fy": 500.0,
"omni:lensdistortion:opencvFisheye:cx": 640.0,
"omni:lensdistortion:opencvFisheye:cy": 360.0,
"omni:lensdistortion:opencvFisheye:k1": 0.05,
"omni:lensdistortion:opencvFisheye:imageSize": Gf.Vec2i(1280, 720),
},
)
Known warnings#
When aux_output_level is set, the following warning may appear in the log:
[usdrt.population.plugin] [UsdNoticeHandler] Unhandled attribute type VtArray<std::string>
(prim attribute: _replicator:rendervar:GenericModelOutput:channels)
This is harmless. The usdrt Fabric cache does not mirror VtArray<std::string> attributes, but the attribute is correctly set on the USD prim and read by the Replicator pipeline.
Integration#
Dependencies include isaacsim.core.experimental.prims (transform and prim utilities), isaacsim.core.experimental.objects (Camera prim wrapper), omni.replicator.core (annotators and writers), omni.sensors.nv.lidar, omni.sensors.nv.radar, omni.sensors.nv.acoustic, omni.sensors.nv.common, omni.sensors.nv.ids, omni.usd.schema.omni_sensors, and isaacsim.storage.native for asset paths. Enable the extension from Window > Extensions and turn on isaacsim.sensors.experimental.rtx.
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.rtx
Define the next entry under [dependencies] in an experience (.kit) file or an extension configuration (extension.toml) file.
[dependencies]
"isaacsim.sensors.experimental.rtx" = {}
Open the Window > Extensions menu in a running application instance and search for isaacsim.sensors.experimental.rtx.
Then, toggle the enable control button if it is not already active.
Extension: {{ extension_version }} |
Documentation Generated: Jun 05, 2026 |
Settings#
Settings Provided by the Extension#
app.sensors.nv.lidar.outputBufferOnGPU#
Default Value: false
Description: Renderer keeps Lidar return buffer on GPU for post-processing.
app.sensors.nv.radar.outputBufferOnGPU#
Default Value: false
Description: Renderer keeps Radar return buffer on GPU for post-processing.
rtx.materialDb.nonVisualMaterialCSV.enabled#
Default Value: false
Description: Enable non-visual materials using USD attributes.
rtx.materialDb.nonVisualMaterialSemantics.prefix#
Default Value: “omni:simready:nonvisual”
Description: Specify the non-visual material USD attribute prefix.
rtx.rtxsensor.useHydraTimeAlways#
Default Value: true
Description: Use Hydra time (
omni.timeline) in RTX sensor models. Applies only if multi-tick rendering is disabled.
Annotators#
The sensor classes included in this extension support, depending on the implementation, a subset of the following annotators (outputs/data products generated by the sensors):
Standard Annotators#
Annotator’s description and outputs are listed in the table below.
Annotator |
Description |
Type / Dtype |
|---|---|---|
|
Bytes encoding a |
|
|
Bytes encoding a Stable ID map (mapping of stable object IDs to prim paths). |
|
Python API#
Warning
The API featured in this extension is experimental and subject to change without deprecation cycles. Although we will try to maintain backward compatibility in the event of a change, it may not always be possible.
The following table summarizes the available classes.
authoring (USD prim wrappers)
High level class for creating/wrapping USD OmniLidar prims. |
|
High level class for creating/wrapping USD OmniRadar prims. |
|
High level class for creating/wrapping USD OmniAcoustic prims. |
|
High level class for creating/wrapping USD Camera prims as RTX sensors. |
|
Structured light camera sensor: an |
sensors (runtime)
Runtime class for operating a single RTX-based lidar sensor. |
|
Runtime class for operating a single RTX-based radar sensor. |
|
Runtime class for operating a single RTX-based acoustic sensor. |
|
High level class for creating/wrapping and operating single camera sensor. |
|
High level class for creating/wrapping and operating single view depth camera sensor. |
|
High level class for creating/wrapping and operating tiled (batched) camera sensors. |
utils
Parse generic model output structure from annotator data. |
|
Parse Stable ID Map data from annotator data. |
lidar configuration
Sensors#
- class LidarSensor(
- path: str | _SensorAuthoring,
- *,
- annotators: Literal['generic-model-output', 'stable-id-map'] | list[Literal['generic-model-output', 'stable-id-map']] | None = None,
- writers: str | list[str] | None = None,
- render_vars: list[str] | None = None,
Bases:
_SensorRuntimeRuntime class for operating a single RTX-based lidar sensor.
Wraps a
Lidarauthoring object, attaches Replicator annotators, and providesget_data()to retrieve sensor output at simulation time.- Parameters:
- Raises:
ValueError – If no prim is found matching the specified path.
ValueError – If the input argument refers to more than one prim.
ValueError – If an unsupported annotator type is specified.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import LidarSensor >>> >>> # given a USD stage with the OmniLidar prim: /World/prim_0 >>> # and a USD Cube prim: /World/cube >>> sensor = LidarSensor( ... "/World/prim_0", ... annotators=["generic-model-output"], ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- class RadarSensor(
- path: str | _SensorAuthoring,
- *,
- annotators: Literal['generic-model-output', 'stable-id-map'] | list[Literal['generic-model-output', 'stable-id-map']] | None = None,
- writers: str | list[str] | None = None,
- render_vars: list[str] | None = None,
Bases:
_SensorRuntimeRuntime class for operating a single RTX-based radar sensor.
Wraps a
Radarauthoring object, attaches Replicator annotators, and providesget_data()to retrieve sensor output at simulation time.Note
RTX Radar requires Motion BVH to be enabled. The setting
/renderer/raytracingMotion/enabledmust be set toTruebefore creating the radar prim.- Parameters:
- Raises:
ValueError – If no prim is found matching the specified path.
ValueError – If the input argument refers to more than one prim.
ValueError – If an unsupported annotator type is specified.
RuntimeError – If Motion BVH is not enabled when creating a new radar prim.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import RadarSensor >>> >>> # given a USD stage with the OmniRadar prim: /World/prim_0 >>> # and a USD Cube prim: /World/cube >>> sensor = RadarSensor( ... "/World/prim_0", ... annotators=["generic-model-output"], ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- class AcousticSensor(
- path: str | _SensorAuthoring,
- *,
- annotators: Literal['generic-model-output', 'stable-id-map'] | list[Literal['generic-model-output', 'stable-id-map']] | None = None,
- writers: str | list[str] | None = None,
- render_vars: list[str] | None = None,
Bases:
_SensorRuntimeRuntime class for operating a single RTX-based acoustic sensor.
Wraps an
Acousticauthoring object, attaches Replicator annotators, and providesget_data()to retrieve sensor output at simulation time.- Parameters:
- Raises:
ValueError – If no prim is found matching the specified path.
ValueError – If the input argument refers to more than one prim.
ValueError – If an unsupported annotator type is specified.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import Acoustic, AcousticSensor >>> >>> # given a USD stage with the OmniAcoustic prim: /World/prim_0 >>> # and a USD Cube prim: /World/cube >>> acoustic = Acoustic("/World/prim_0", aux_output_level="BASIC") >>> sensor = AcousticSensor( ... acoustic, ... annotators=["generic-model-output"], ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- class CameraSensor(
- path: str | RtxCamera,
- *,
- resolution: tuple[int, int],
- annotators: Literal['bounding_box_2d_loose', 'bounding_box_2d_tight', 'bounding_box_3d', 'distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'pointcloud', 'rgb', 'rgba', 'semantic_segmentation'] | list[Literal['bounding_box_2d_loose', 'bounding_box_2d_tight', 'bounding_box_3d', 'distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'pointcloud', 'rgb', 'rgba', 'semantic_segmentation']] | None = None,
- writers: str | list[str] | None = None,
- render_vars: list[str] | None = None,
Bases:
_SensorRuntimeHigh level class for creating/wrapping and operating single camera sensor.
- Parameters:
- Raises:
ValueError – If no prim is found matching the specified path.
ValueError – If the input argument refers to more than one camera prim.
ValueError – If an unsupported annotator type is specified.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import CameraSensor >>> >>> # given a USD stage with the Camera prim: /World/prim_0 >>> resolution = (240, 320) # following OpenCV/NumPy convention `(height, width)` >>> camera_sensor = CameraSensor( ... "/World/prim_0", ... resolution=resolution, ... annotators=["rgb", "distance_to_image_plane"], ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- attach_annotators(annotators: str | list[str]) None#
Attach annotators to the sensor.
- Parameters:
annotators – Annotator/sensor types to attach.
- Raises:
ValueError – If the specified annotator is not supported.
- get_data(
- annotator: str,
- *,
- out: wp.array | None = None,
Fetch the specified annotator/sensor data for the camera.
- Parameters:
annotator – Annotator/sensor type from which fetch the data.
out – Pre-allocated array to fill with the fetched data.
- Returns:
Two-elements tuple. 1) Array containing the fetched data. If no data is available at the moment of calling the method,
Noneis returned. 2) Dictionary containing additional information according to the requested annotator/sensor.- Raises:
ValueError – If the specified annotator is not supported.
ValueError – If the specified annotator is not configured.
- property camera: Any#
Camera object for accessing optical parameters.
- Returns:
Camera object wrapping the sensor prim.
- property resolution: tuple[int, int]#
Resolution of the sensor.
- Returns:
(height, width)).- Return type:
Resolution of sensor frames (following OpenCV/NumPy convention
- class SingleViewDepthCameraSensor(
- path: str | RtxCamera,
- *,
- resolution: tuple[int, int],
- annotators: Literal['bounding_box_2d_loose', 'bounding_box_2d_tight', 'bounding_box_3d', 'distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'pointcloud', 'semantic_segmentation', 'depth_sensor_distance', 'depth_sensor_imager', 'depth_sensor_point_cloud_color', 'depth_sensor_point_cloud_position'] | list[Literal['bounding_box_2d_loose', 'bounding_box_2d_tight', 'bounding_box_3d', 'distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'pointcloud', 'semantic_segmentation', 'depth_sensor_distance', 'depth_sensor_imager', 'depth_sensor_point_cloud_color', 'depth_sensor_point_cloud_position']],
Bases:
CameraSensorHigh level class for creating/wrapping and operating single view depth camera sensor.
The sensor is modeled using a single camera view to simulate a stereo camera pair and compute disparity and depth. The sensor is implemented as a post-process operation in the renderer, where the OmniSensorDepthSensorSingleViewAPI schema is applied to the USD render product prim rather than to the camera prim.
- Parameters:
path –
Cameraobject or single path to existing or non-existing (one of both) USD Camera prim. Can include regular expression for matching a prim.resolution – Resolution of the sensor (following OpenCV/NumPy convention:
(height, width)).annotators – Annotator/sensor types to configure.
- Raises:
ValueError – If no prim is found matching the specified path.
ValueError – If the input argument refers to more than one camera prim.
ValueError – If an unsupported annotator type is specified.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import SingleViewDepthCameraSensor >>> >>> # given a USD stage with the Camera prim: /World/prim_0 >>> resolution = (240, 320) # following OpenCV/NumPy convention `(height, width)` >>> camera_sensor = SingleViewDepthCameraSensor( ... "/World/prim_0", ... resolution=resolution, ... annotators="depth_sensor_distance", ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- static add_template_render_product(
- parent_prim_path: str,
- camera_prim_path: str,
- **kwargs: Any,
Add a template render product for a depth sensor to the USD stage.
Creates a
RenderProductprim withOmniSensorDepthSensorSingleViewAPIapplied and acamerarelationship pointing to the given camera prim. The render product is created as a child ofparent_prim_pathand is named<camera_name>_render_product.This is used when building a depth camera USD asset for later use with
SingleViewDepthCameraSensor. When the asset is loaded viaRtxCamera.create(),SingleViewDepthCameraSensorautomatically detects the embedded render product and copies its depth sensor attributes onto the dynamically created render product.- Parameters:
parent_prim_path – USD path to the parent prim under which the
RenderProductwill be created (trailing slash is stripped automatically).camera_prim_path – USD path to the
Cameraprim to associate with theRenderProduct.**kwargs – Depth sensor attribute names and values to set on the
RenderProduct(e.g.omni:rtx:post:depthSensor:baselineMM=42). A warning is logged for any key that does not correspond to an existing attribute on the prim.
- Returns:
The created
RenderProductprim, or an invalidpxr.Usd.Primif creation failed.
Example:
>>> SingleViewDepthCameraSensor.add_template_render_product( ... parent_prim_path="/root/TemplateRenderProduct", ... camera_prim_path="/root/Camera", ... **{"omni:rtx:post:depthSensor:baselineMM": 42}, ... )
- get_enabled_outlier_removal() bool#
Get the enabled state of the outlier removal filter of the depth sensor.
Filter out single pixel samples caused by antialiasing jitter and reprojection resolution.
- Returns:
Boolean flag indicating if the outlier removal filter is enabled.
Example:
>>> camera_sensor.get_enabled_outlier_removal() True
- get_enabled_post_processing() bool#
Get the enabled state of the post-process operation for depth sensing in the renderer of the prims.
- Returns:
Boolean flag indicating if the depth sensor post-process is enabled.
Example:
>>> camera_sensor.get_enabled_post_processing() True
- get_sensor_baseline() float#
Get the distance between the simulated depth camera sensor, in millimeters.
Larger positive/negative values will increase the unknown black/hole regions around objects where the depth camera sensor cannot see.
- Returns:
The distance between the simulated depth camera sensor, in millimeters.
Example:
>>> camera_sensor.get_sensor_baseline() 55.0
- get_sensor_disparity_confidence() float#
Get the confidence threshold for the depth sensor.
Control how likely a depth sample is considered valid. Higher values make depth values vary wider across the quantization (noise mean) range.
- Returns:
The confidence threshold for the depth sensor.
Example:
>>> camera_sensor.get_sensor_disparity_confidence() 0.6999...
- get_sensor_disparity_noise_downscale() float#
Get the coarseness of the disparity noise, in pixels, of the depth sensor.
Higher values reduce the spatial resolution of the noise.
- Returns:
The disparity noise downscale factor, in pixels.
Example:
>>> camera_sensor.get_sensor_disparity_noise_downscale() 1.0
- get_sensor_distance_cutoffs() tuple[float, float]#
Get the cutoff range (minimum and maximum distance) of the depth sensor.
- Returns:
The minimum cutoff distance. The maximum cutoff distance.
Example:
>>> camera_sensor.get_sensor_distance_cutoffs() (0.5, 10000000.0)
- get_sensor_focal_length() float#
Get the simulated focal length of the depth sensor, in pixels.
Combined with the sensor size, this sets the field of view for the disparity calculation. Since the actual FOV is controlled on the camera prim, this only adjusts the amount of left/right disparity. Lower focal length decreases disparity.
- Returns:
The sensor focal length, in pixels.
Example:
>>> camera_sensor.get_sensor_focal_length() 897.0
- get_sensor_maximum_disparity() float#
Get the maximum number of disparity pixels for the depth sensor.
Higher values allow the sensor to resolve closer (more disparate) objects. Lower values reduce the depth sensing range.
- Returns:
The maximum number of disparity pixels for the depth sensor.
Example:
>>> camera_sensor.get_sensor_maximum_disparity() 110.0
- get_sensor_noise_parameters() tuple[float, float]#
Get the quantization factor (mean and sigma) for the disparity noise, in pixels, of the depth sensor.
- Returns:
Two-elements tuple. 1) The disparity noise mean value, in pixels. 2) The disparity noise sigma value, in pixels.
Example:
>>> camera_sensor.get_sensor_noise_parameters() (0.25, 0.25)
- get_sensor_output_mode() int#
Get the output mode used to override the LDRColor buffer with a debug visualization of the depth sensor.
Supported modes:
0: Pass through LDRColor.1: Repeated 1 meter grayscale gradient.2: Grayscale gradient over min/max distance.3: Rainbow gradient over min/max distance.4: Input Depth values in grayscale.5: Reprojected depth with confidence culling applied.6: Confidence Map with Disparity.7: Disparity values in grayscale.
- Returns:
The output mode.
Example:
>>> camera_sensor.get_sensor_output_mode() 0
- get_sensor_size() float#
Get the size of the sensor, in pixels, of the depth sensor.
Combined with focal length, this affects the amount of disparity. Higher values decrease disparity.
- Returns:
The sensor size, in pixels.
Example:
>>> camera_sensor.get_sensor_size() 1280.0
- set_enabled_outlier_removal(
- enabled: bool,
Enable or disable the outlier removal filter of the depth sensor.
Filter out single pixel samples caused by antialiasing jitter and reprojection resolution.
- Parameters:
enabled – Boolean flag to enable/disable outlier removal.
Example:
>>> camera_sensor.set_enabled_outlier_removal(True)
- set_enabled_post_processing(
- enabled: bool,
Enable or disable the post-process operation for depth sensing in the renderer.
- Parameters:
enabled – Boolean flag to enable/disable the depth sensor post-process.
Example:
>>> camera_sensor.set_enabled_post_processing(True)
- set_sensor_baseline(
- baseline: float,
Set the distance between the simulated depth camera sensor, in millimeters.
Larger positive/negative values will increase the unknown black/hole regions around objects where the camera sensor cannot see.
- Parameters:
baseline – Sensor baseline in millimeters.
Example:
>>> camera_sensor.set_sensor_baseline(50.0)
- set_sensor_disparity_confidence(
- confidence_threshold: float,
Set the confidence threshold for the depth sensor.
Control how likely a depth sample is considered valid. Higher values make depth values vary wider across the quantization (noise mean) range.
- Parameters:
confidence_threshold – Confidence threshold.
Example:
>>> camera_sensor.set_sensor_disparity_confidence(0.75)
- set_sensor_disparity_noise_downscale(
- downscale: float,
Set the coarseness of the disparity noise, in pixels, of the depth sensor.
Higher values reduce the spatial resolution of the noise.
- Parameters:
downscale – Disparity noise downscale factor in pixels.
Example:
>>> camera_sensor.set_sensor_disparity_noise_downscale(1.5)
- set_sensor_distance_cutoffs(
- minimum_distance: float = None,
- maximum_distance: float = None,
Set the cutoff range (minimum and maximum distance) of the depth sensor.
- Parameters:
minimum_distance – Minimum cutoff distance.
maximum_distance – Maximum cutoff distance.
- Raises:
ValueError – If both
minimum_distanceandmaximum_distanceare not defined.
Example:
>>> camera_sensor.set_sensor_distance_cutoffs(minimum_distance=0.1, maximum_distance=1000000.0)
- set_sensor_focal_length(
- focal_length: float,
Set the simulated focal length of the depth sensor, in pixels.
Combined with the sensor size, this sets the field of view for the disparity calculation. Since the actual FOV is controlled on the camera prim, this only adjusts the amount of left/right disparity. Lower focal length decreases disparity.
- Parameters:
focal_length – Sensor focal length in pixels.
Example:
>>> camera_sensor.set_sensor_focal_length(800.0)
- set_sensor_maximum_disparity(
- maximum_disparity: float,
Set the maximum number of disparity pixels for the depth sensor.
Higher values allow the sensor to resolve closer (more disparate) objects. Lower values reduce the depth sensing range.
- Parameters:
maximum_disparity – Maximum disparity.
Example:
>>> camera_sensor.set_sensor_maximum_disparity(120.0)
- set_sensor_noise_parameters(
- noise_mean: float = None,
- noise_sigma: float = None,
Set the quantization factor (mean and sigma) for the disparity noise, in pixels, of the depth sensor.
Higher mean values reduce depth resolution. Higher sigma values make depth values vary wider across the quantization (noise mean) range.
- Parameters:
noise_mean – Disparity noise mean value in pixels.
noise_sigma – Disparity noise sigma value in pixels.
- Raises:
AssertionError – If neither
noise_meannornoise_sigmaare specified.
Example:
>>> camera_sensor.set_sensor_noise_parameters(noise_mean=0.5, noise_sigma=0.1)
- set_sensor_output_mode(mode: int) None#
Set the output mode to override the LDRColor buffer with a debug visualization of the depth sensor.
Supported modes:
0: Pass through LDRColor.1: Repeated 1 meter grayscale gradient.2: Grayscale gradient over min/max distance.3: Rainbow gradient over min/max distance.4: Input Depth values in grayscale.5: Reprojected depth with confidence culling applied.6: Confidence Map with Disparity.7: Disparity values in grayscale.
- Parameters:
mode – Output mode.
Example:
>>> camera_sensor.set_sensor_output_mode(0) # pass through LDRColor
- class TiledCameraSensor(
- paths: str | list[str] | Camera,
- *,
- resolution: tuple[int, int],
- annotators: Literal['distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'rgb', 'rgba', 'semantic_segmentation'] | list[Literal['distance_to_camera', 'distance_to_image_plane', 'instance_id_segmentation', 'instance_segmentation', 'motion_vectors', 'normals', 'rgb', 'rgba', 'semantic_segmentation']],
- render_vars: list[str] | None = None,
Bases:
objectHigh level class for creating/wrapping and operating tiled (batched) camera sensors.
- Parameters:
paths –
Cameraobject, single path or list of paths to existing or non-existing (one of both) USD Camera prims. Can include regular expressions for matching multiple prims.resolution – Resolution of each individual sensor (following OpenCV/NumPy convention:
(height, width)).annotators – Annotator/sensor types to configure.
- Raises:
ValueError – If no prims are found matching the specified paths.
ValueError – If an unsupported annotator type is specified.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> from isaacsim.sensors.experimental.rtx import TiledCameraSensor >>> >>> # given a USD stage with the Camera prims: /World/prim_0, /World/prim_1, and /World/prim_2 >>> resolution = (240, 320) # following OpenCV/NumPy convention `(height, width)` >>> tiled_camera_sensor = TiledCameraSensor( ... "/World/prim_.*", ... resolution=resolution, ... annotators=["rgb", "distance_to_image_plane"], ... ) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True)
- attach_annotators(
- annotators: str | list[str],
Attach annotators to the sensor.
- Parameters:
annotators – Annotator/sensor types to attach.
- Raises:
ValueError – If the specified annotator is not supported.
Example:
>>> tiled_camera_sensor.annotators ['distance_to_image_plane', 'rgb'] >>> tiled_camera_sensor.attach_annotators("normals") >>> tiled_camera_sensor.annotators ['distance_to_image_plane', 'normals', 'rgb']
- detach_annotators(
- annotators: str | list[str],
Detach annotators from the sensor.
- Parameters:
annotators – Annotator/sensor types to detach. If the annotator is not attached, or it has already been detached, a warning is logged and the method does nothing.
- Raises:
ValueError – If the specified annotator is not supported.
Example:
>>> tiled_camera_sensor.annotators ['distance_to_image_plane', 'normals', 'rgb'] >>> tiled_camera_sensor.detach_annotators(["distance_to_image_plane", "normals"]) >>> tiled_camera_sensor.annotators ['rgb']
- get_data(
- annotator: str,
- *,
- tiled: bool = False,
- out: wp.array | None = None,
Fetch the specified annotator/sensor data for all cameras as a batch of frames or as a single tiled frame.
- Parameters:
annotator – Annotator/sensor type from which fetch the data.
tiled – Whether to get annotator/sensor data as a single tiled frame.
out – Pre-allocated array to fill with the fetched data.
- Returns:
Two-elements tuple. 1) Array containing the fetched data. If
outis defined, such instance is returned filled with the data. If no data is available at the moment of calling the method,Noneis returned. 2) Dictionary containing additional information according to the requested annotator/sensor.- Raises:
ValueError – If the specified annotator is not supported.
ValueError – If the specified annotator is not configured when instantiating the object.
Example:
>>> data, info = tiled_camera_sensor.get_data("rgb") >>> data.shape (3, 240, 320, 3) >>> info {}
- property annotators: list[str]#
Annotators.
- Returns:
Sorted list of registered annotators.
Example:
>>> tiled_camera_sensor.annotators ['distance_to_image_plane', 'rgb']
- property camera: Camera#
Camera object encapsulated by the sensor.
- Returns:
Camera object encapsulated by the sensor.
Example:
>>> tiled_camera_sensor.camera <isaacsim.core.experimental.objects.impl.camera.Camera object at 0x...>
- property render_product: pxr.UsdRender.Product#
Render product.
- Returns:
Render product of the tiled camera sensor.
Example:
>>> tiled_camera_sensor.render_product UsdRender.Product(Usd.Prim(</Render/OmniverseKit/HydraTextures/tiled_camera_sensor_...>))
- property resolution: tuple[int, int]#
Resolution of individual batched frames.
- Returns:
(height, width)).- Return type:
Resolution of individual batched frames (following OpenCV/NumPy convention
Example:
>>> tiled_camera_sensor.resolution (240, 320)
- property tiled_resolution: tuple[int, int]#
Resolution of tiled frames.
- Returns:
(height, width)).- Return type:
Resolution of tiled frames (following OpenCV/NumPy convention
Example:
>>> tiled_camera_sensor.tiled_resolution (480, 640)
Utils#
- parse_generic_model_output_data(
- data: warp.array,
Parse generic model output structure from annotator data.
- Parameters:
data – generic-model-output data from an annotator.
- Returns:
Generic model output structure.
Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> import isaacsim.core.experimental.utils.stage as stage_utils >>> from isaacsim.sensors.experimental.rtx import LidarSensor, parse_generic_model_output_data >>> >>> stage_utils.define_prim("/World/sphere", "Sphere") >>> sensor = LidarSensor("/World/lidar", annotators=["generic-model-output"]) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True) >>> >>> data, _ = sensor.get_data("generic-model-output") >>> parse_generic_model_output_data(data) <generic_model_output.GenericModelOutput object at 0x...>
- parse_stable_id_map_data(data: warp.array) dict#
Parse Stable ID Map data from annotator data.
- Parameters:
data – stable-id-map annotator data.
- Returns:
Dictionary mapping stable IDs to their prim paths.
Warning
Some object IDs returned by the LiDAR may not have an entry in this map. The renderer emits each 128-bit stable ID as a per-instance base ID combined with an “upper index” in the high 32 bits — the submesh index for mesh geometry and the per-triangle primitive index for procedural geometry. The map registers per- instance entries and (when
subsetCount > 1) per-GeomSubsetentries, but it does not register per-primitive entries, so hits on procedural geometry, on submeshes that weren’t expanded, or on renderer-internal instances without a USD prim path will produce IDs with no map entry, and a directmap[id]lookup will raiseKeyError. Usemap.get(id, "<unknown>")to handle missing IDs gracefully — see the bundledresolve_lidar_object_ids.pyexample for the recommended pattern.Example:
>>> import isaacsim.core.experimental.utils.app as app_utils >>> import isaacsim.core.experimental.utils.stage as stage_utils >>> from isaacsim.sensors.experimental.rtx import LidarSensor, parse_stable_id_map_data >>> >>> stage_utils.define_prim("/World/sphere", "Sphere") >>> sensor = LidarSensor("/World/lidar", annotators=["stable-id-map"]) >>> >>> # play the simulation so the sensor can fetch data >>> app_utils.play(commit=True) >>> >>> data, _ = sensor.get_data("stable-id-map") >>> parse_stable_id_map_data(data) {0: '/World/sphere'}
Lidar configuration registry#
- SUPPORTED_LIDAR_CONFIGS#
Mapping from known Isaac Sim lidar asset paths to optional variant name sets.
- SUPPORTED_LIDAR_VARIANT_SET_NAME#
Variant set name expected on supported lidar prims.