From e8fc9f00dc4c16b2656d5b5113d7f610380496e3 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Wed, 22 Apr 2026 22:28:25 -0700 Subject: [PATCH 1/7] Separate render backend specific code from Camera --- .../isaaclab/renderers/base_renderer.py | 27 ++++ .../isaaclab/sensors/camera/camera.py | 142 ++++-------------- .../isaaclab/sensors/camera/camera_cfg.py | 63 ++++++++ .../test/renderers/test_renderer_factory.py | 3 + source/isaaclab/test/sensors/test_camera.py | 28 ++-- .../renderers/newton_warp_renderer.py | 33 ++++ .../renderers/newton_warp_renderer_cfg.py | 3 + .../isaaclab_ov/renderers/ovrtx_renderer.py | 118 ++++++++++----- .../renderers/isaac_rtx_renderer.py | 96 ++++++++++-- .../renderers/isaac_rtx_renderer_cfg.py | 77 +++++++++- 10 files changed, 416 insertions(+), 174 deletions(-) diff --git a/source/isaaclab/isaaclab/renderers/base_renderer.py b/source/isaaclab/isaaclab/renderers/base_renderer.py index 7725f0a4fdaa..900ef80ffdb7 100644 --- a/source/isaaclab/isaaclab/renderers/base_renderer.py +++ b/source/isaaclab/isaaclab/renderers/base_renderer.py @@ -20,6 +20,33 @@ class BaseRenderer(ABC): """Abstract base class for renderer implementations.""" + @abstractmethod + def create_output_buffers( + self, + data_types: list[str], + height: int, + width: int, + num_views: int, + device: torch.device | str, + ) -> dict[str, torch.Tensor]: + """Allocate output tensors for the supported subset of ``data_types``. + + Implementations MUST omit any data-type names they cannot produce and + allocate on ``device``. They MAY include aliased entries that share + storage with another entry (e.g. ``rgb`` as a view into ``rgba``). + + Args: + data_types: Names of the requested data types. + height: Image height in pixels. + width: Image width in pixels. + num_views: Number of camera views (batch dimension). + device: Torch device on which to allocate the buffers. + + Returns: + Mapping from data-type name to a pre-allocated tensor. + """ + pass + @abstractmethod def prepare_stage(self, stage: Any, num_envs: int) -> None: """Prepare the stage for rendering before create_render_data is called. diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index eb588489f729..abb02970d67b 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -12,22 +12,20 @@ import numpy as np import torch import warp as wp -from packaging import version -from pxr import Sdf, UsdGeom +from pxr import UsdGeom import isaaclab.sim as sim_utils import isaaclab.utils.sensors as sensor_utils from isaaclab.app.settings_manager import get_settings_manager from isaaclab.renderers import BaseRenderer, Renderer from isaaclab.sim.views import XformPrimView -from isaaclab.utils import has_kit, to_camel_case +from isaaclab.utils import to_camel_case from isaaclab.utils.math import ( convert_camera_frame_orientation_convention, create_rotation_matrix_from_view, quat_from_matrix, ) -from isaaclab.utils.version import get_isaac_sim_version from ..sensor_base import SensorBase from .camera_data import CameraData @@ -95,12 +93,6 @@ class Camera(SensorBase): } """The set of sensor types that are not supported by the camera class.""" - SIMPLE_SHADING_TYPES: set[str] = { - "simple_shading_constant_diffuse", - "simple_shading_diffuse_mdl", - "simple_shading_full_mdl", - } - def __init__(self, cfg: CameraCfg): """Initializes the camera sensor. @@ -116,10 +108,15 @@ def __init__(self, cfg: CameraCfg): # initialize base class super().__init__(cfg) - # toggle rendering of rtx sensors as True - # this flag is read by SimulationContext to determine if rtx sensors should be rendered - settings = get_settings_manager() - settings.set_bool("/isaaclab/render/rtx_sensors", True) + # TODO: Camera should not branch on a specific renderer_type string. Replace with a + # generic opt-in flag on RendererCfg (e.g. ``requires_kit_rtx_sensors_flag``) that + # RTX-family cfgs set to True, so this branch carries no renderer-specific knowledge. + # The flag must flip at scene-construction time (before sim.reset()) because + # SimulationContext.is_rendering and several env classes branch on it pre-reset; + # flipping inside the renderer's __init__ (which only runs at sim.reset()) would + # silently break that timing. + if self.cfg.renderer_cfg.renderer_type == "isaac_rtx": + get_settings_manager().set_bool("/isaaclab/render/rtx_sensors", True) # spawn the asset if self.cfg.spawn is not None: @@ -160,22 +157,6 @@ def __init__(self, cfg: CameraCfg): self._renderer: BaseRenderer | None = None self._render_data = None - if not has_kit(): - return - # HACK: We need to disable instancing for semantic_segmentation and instance_segmentation_fast to work - # checks for Isaac Sim v4.5 as this issue exists there - if get_isaac_sim_version() == version.parse("4.5"): - if "semantic_segmentation" in self.cfg.data_types or "instance_segmentation_fast" in self.cfg.data_types: - logger.warning( - "Isaac Sim 4.5 introduced a bug in Camera and TiledCamera when outputting instance and semantic" - " segmentation outputs for instanceable assets. As a workaround, the instanceable flag on assets" - " will be disabled in the current workflow and may lead to longer load times and increased memory" - " usage." - ) - with Sdf.ChangeBlock(): - for prim in self.stage.Traverse(): - prim.SetInstanceable(False) - def __del__(self): """Unsubscribes from callbacks and cleans up renderer resources.""" # unsubscribe callbacks @@ -190,10 +171,6 @@ def __str__(self) -> str: return ( f"Camera @ '{self.cfg.prim_path}': \n" f"\tdata types : {list(self.data.output.keys())} \n" - f"\tsemantic filter : {self.cfg.semantic_filter}\n" - f"\tcolorize semantic segm. : {self.cfg.colorize_semantic_segmentation}\n" - f"\tcolorize instance segm. : {self.cfg.colorize_instance_segmentation}\n" - f"\tcolorize instance id segm.: {self.cfg.colorize_instance_id_segmentation}\n" f"\tupdate period (s): {self.cfg.update_period}\n" f"\tshape : {self.image_shape}\n" f"\tnumber of sensors : {self._view.count}" @@ -396,16 +373,10 @@ def _initialize_impl(self): Raises: RuntimeError: If the number of camera prims in the view does not match the number of environments. - RuntimeError: If cameras are not enabled (missing ``--enable_cameras`` flag). + RuntimeError: Propagated from the renderer constructor when the active backend's + runtime requirements are not satisfied (e.g. the RTX backend requires the + simulation app to be launched with ``--enable_cameras``). """ - renderer_type = getattr(self.cfg.renderer_cfg, "renderer_type", "default") - needs_kit_cameras = renderer_type in ("default", "isaac_rtx") - if needs_kit_cameras and not get_settings_manager().get("/isaaclab/cameras_enabled"): - raise RuntimeError( - "A camera was spawned without the --enable_cameras flag. Please use --enable_cameras to enable" - " rendering." - ) - # Initialize parent class super()._initialize_impl() @@ -498,73 +469,24 @@ def _create_buffers(self): self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device) self._update_poses(self._ALL_INDICES) self._data.image_shape = self.image_shape - # -- output data (eagerly pre-allocated so renderer.set_outputs() can hold tensor references) - data_dict = dict() - if "rgba" in self.cfg.data_types or "rgb" in self.cfg.data_types: - data_dict["rgba"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 4), device=self.device, dtype=torch.uint8 - ).contiguous() - if "rgb" in self.cfg.data_types: - data_dict["rgb"] = data_dict["rgba"][..., :3] - if "albedo" in self.cfg.data_types: - data_dict["albedo"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 4), device=self.device, dtype=torch.uint8 - ).contiguous() - for data_type in self.SIMPLE_SHADING_TYPES: - if data_type in self.cfg.data_types: - data_dict[data_type] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 3), device=self.device, dtype=torch.uint8 - ).contiguous() - if "distance_to_image_plane" in self.cfg.data_types: - data_dict["distance_to_image_plane"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.float32 - ).contiguous() - if "depth" in self.cfg.data_types: - data_dict["depth"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.float32 - ).contiguous() - if "distance_to_camera" in self.cfg.data_types: - data_dict["distance_to_camera"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.float32 - ).contiguous() - if "normals" in self.cfg.data_types: - data_dict["normals"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 3), device=self.device, dtype=torch.float32 - ).contiguous() - if "motion_vectors" in self.cfg.data_types: - data_dict["motion_vectors"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 2), device=self.device, dtype=torch.float32 - ).contiguous() - if "semantic_segmentation" in self.cfg.data_types: - if self.cfg.colorize_semantic_segmentation: - data_dict["semantic_segmentation"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 4), device=self.device, dtype=torch.uint8 - ).contiguous() - else: - data_dict["semantic_segmentation"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.int32 - ).contiguous() - if "instance_segmentation_fast" in self.cfg.data_types: - if self.cfg.colorize_instance_segmentation: - data_dict["instance_segmentation_fast"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 4), device=self.device, dtype=torch.uint8 - ).contiguous() - else: - data_dict["instance_segmentation_fast"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.int32 - ).contiguous() - if "instance_id_segmentation_fast" in self.cfg.data_types: - if self.cfg.colorize_instance_id_segmentation: - data_dict["instance_id_segmentation_fast"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 4), device=self.device, dtype=torch.uint8 - ).contiguous() - else: - data_dict["instance_id_segmentation_fast"] = torch.zeros( - (self._view.count, self.cfg.height, self.cfg.width, 1), device=self.device, dtype=torch.int32 - ).contiguous() - - self._data.output = data_dict - self._data.info = {name: None for name in self.cfg.data_types} + # -- output data: ask the renderer to allocate buffers for the requested data types. + buffers = self._renderer.create_output_buffers( + self.cfg.data_types, + self.cfg.height, + self.cfg.width, + self._view.count, + self.device, + ) + # Surface any requested data types the active renderer cannot produce. + unsupported = [name for name in self.cfg.data_types if name not in buffers] + if unsupported: + logger.warning( + "Renderer %s does not support the following requested data types and will not produce them: %s", + type(self._renderer).__name__, + unsupported, + ) + self._data.output = buffers + self._data.info = {name: None for name in buffers} self._renderer.set_outputs(self._render_data, self._data.output) def _update_intrinsic_matrices(self, env_ids: Sequence[int]): diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index 1b5070cfd214..392575ff6492 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -5,6 +5,7 @@ from __future__ import annotations +import warnings from dataclasses import MISSING, field from typing import TYPE_CHECKING, Literal @@ -19,6 +20,18 @@ if TYPE_CHECKING: from .camera import Camera +# Default values for the RTX-flavored fields kept on :class:`CameraCfg` for +# backward compatibility. These mirror the defaults on +# :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg`. +_DEPRECATED_RENDERER_FIELD_DEFAULTS: dict = { + "semantic_filter": "*:*", + "colorize_semantic_segmentation": True, + "colorize_instance_id_segmentation": True, + "colorize_instance_segmentation": True, + "semantic_segmentation_mapping": {}, + "depth_clipping_behavior": "none", +} + @configclass class CameraCfg(SensorBaseCfg): @@ -67,6 +80,11 @@ class OffsetCfg: - ``"max"``: Values are clipped to the maximum value. - ``"zero"``: Values are clipped to zero. - ``"none``: No clipping is applied. Values will be returned as ``inf``. + + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.depth_clipping_behavior` + on :attr:`renderer_cfg` instead. """ data_types: list[str] = ["rgb"] @@ -108,6 +126,11 @@ class OffsetCfg: For more information on the semantics filter, see the documentation on `Replicator Semantics Schema Editor`_. .. _Replicator Semantics Schema Editor: https://docs.omniverse.nvidia.com/extensions/latest/ext_replicator/semantics_schema_editor.html#semantics-filtering + + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.semantic_filter` on + :attr:`renderer_cfg` instead. """ colorize_semantic_segmentation: bool = True @@ -115,6 +138,11 @@ class OffsetCfg: If True, semantic segmentation is converted to an image where semantic IDs are mapped to colors and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_semantic_segmentation` + on :attr:`renderer_cfg` instead. """ colorize_instance_id_segmentation: bool = True @@ -122,6 +150,11 @@ class OffsetCfg: If True, instance id segmentation is converted to an image where instance IDs are mapped to colors. and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_instance_id_segmentation` + on :attr:`renderer_cfg` instead. """ colorize_instance_segmentation: bool = True @@ -129,6 +162,11 @@ class OffsetCfg: If True, instance segmentation is converted to an image where instance IDs are mapped to colors. and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_instance_segmentation` + on :attr:`renderer_cfg` instead. """ semantic_segmentation_mapping: dict = {} @@ -147,7 +185,32 @@ class OffsetCfg: "class:robot": (61, 178, 255, 255), } + .. deprecated:: 4.7.0 + This field is RTX-specific. Set + :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.semantic_segmentation_mapping` + on :attr:`renderer_cfg` instead. """ renderer_cfg: RendererCfg = field(default_factory=IsaacRtxRendererCfg) """Renderer configuration for camera sensor.""" + + def __post_init__(self): + """Forward deprecated RTX-flavored fields onto :attr:`renderer_cfg`. + + Each deprecated field set to a non-default value emits a + :class:`DeprecationWarning` and is copied onto ``self.renderer_cfg`` + when that cfg defines the same-named field. + """ + # Forwarded by name: any same-named field on ``renderer_cfg`` will receive the value. + for field_name, default in _DEPRECATED_RENDERER_FIELD_DEFAULTS.items(): + value = getattr(self, field_name) + if value == default: + continue + warnings.warn( + f"CameraCfg.{field_name} is deprecated and will be removed in a future release." + f" Set this field on CameraCfg.renderer_cfg instead.", + DeprecationWarning, + stacklevel=2, + ) + if hasattr(self.renderer_cfg, field_name): + setattr(self.renderer_cfg, field_name, value) diff --git a/source/isaaclab/test/renderers/test_renderer_factory.py b/source/isaaclab/test/renderers/test_renderer_factory.py index 1a38a7fa1c50..e5ded56e6e34 100644 --- a/source/isaaclab/test/renderers/test_renderer_factory.py +++ b/source/isaaclab/test/renderers/test_renderer_factory.py @@ -28,6 +28,9 @@ class MockRenderer(BaseRenderer): def __init__(self, cfg=None): pass + def create_output_buffers(self, data_types, height, width, num_views, device): + return {} + def prepare_stage(self, stage, num_envs): pass diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 023f20b0a5fc..926492450ed0 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -406,12 +406,12 @@ def test_depth_clipping(setup_sim_camera): camera_cfg_none = copy.deepcopy(camera_cfg_zero) camera_cfg_none.prim_path = "/World/CameraNone" - camera_cfg_none.depth_clipping_behavior = "none" + camera_cfg_none.renderer_cfg.depth_clipping_behavior = "none" camera_none = Camera(camera_cfg_none) camera_cfg_max = copy.deepcopy(camera_cfg_zero) camera_cfg_max.prim_path = "/World/CameraMax" - camera_cfg_max.depth_clipping_behavior = "max" + camera_cfg_max.renderer_cfg.depth_clipping_behavior = "max" camera_max = Camera(camera_cfg_max) # Play sim @@ -502,9 +502,9 @@ def test_camera_resolution_all_colorize(setup_sim_camera): "instance_segmentation_fast", "instance_id_segmentation_fast", ] - camera_cfg.colorize_instance_id_segmentation = True - camera_cfg.colorize_instance_segmentation = True - camera_cfg.colorize_semantic_segmentation = True + camera_cfg.renderer_cfg.colorize_instance_id_segmentation = True + camera_cfg.renderer_cfg.colorize_instance_segmentation = True + camera_cfg.renderer_cfg.colorize_semantic_segmentation = True # Create camera camera = Camera(camera_cfg) @@ -564,9 +564,9 @@ def test_camera_resolution_no_colorize(setup_sim_camera): "instance_segmentation_fast", "instance_id_segmentation_fast", ] - camera_cfg.colorize_instance_id_segmentation = False - camera_cfg.colorize_instance_segmentation = False - camera_cfg.colorize_semantic_segmentation = False + camera_cfg.renderer_cfg.colorize_instance_id_segmentation = False + camera_cfg.renderer_cfg.colorize_instance_segmentation = False + camera_cfg.renderer_cfg.colorize_semantic_segmentation = False # Create camera camera = Camera(camera_cfg) @@ -625,9 +625,9 @@ def test_camera_large_resolution_all_colorize(setup_sim_camera): "instance_segmentation_fast", "instance_id_segmentation_fast", ] - camera_cfg.colorize_instance_id_segmentation = True - camera_cfg.colorize_instance_segmentation = True - camera_cfg.colorize_semantic_segmentation = True + camera_cfg.renderer_cfg.colorize_instance_id_segmentation = True + camera_cfg.renderer_cfg.colorize_instance_segmentation = True + camera_cfg.renderer_cfg.colorize_semantic_segmentation = True camera_cfg.width = 512 camera_cfg.height = 512 # Create camera @@ -958,9 +958,9 @@ def test_camera_segmentation_non_colorize(setup_camera_device, device): camera_cfg = copy.deepcopy(camera_cfg) camera_cfg.data_types = ["semantic_segmentation", "instance_segmentation_fast", "instance_id_segmentation_fast"] camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera_cfg.colorize_semantic_segmentation = False - camera_cfg.colorize_instance_segmentation = False - camera_cfg.colorize_instance_id_segmentation = False + camera_cfg.renderer_cfg.colorize_semantic_segmentation = False + camera_cfg.renderer_cfg.colorize_instance_segmentation = False + camera_cfg.renderer_cfg.colorize_instance_id_segmentation = False camera = Camera(camera_cfg) sim.reset() diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index a870f0ae0530..6a3f6718b786 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -216,6 +216,39 @@ def __init__(self, cfg: NewtonWarpRendererCfg): if cfg.create_default_light: self.newton_sensor.utils.create_default_light(enable_shadows=cfg.enable_shadows) + def create_output_buffers( + self, + data_types: list[str], + height: int, + width: int, + num_views: int, + device: torch.device | str, + ) -> dict[str, torch.Tensor]: + """Allocate output tensors for the data types Newton Warp can produce. + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" + buffers: dict[str, torch.Tensor] = {} + requested = set(data_types) + names = RenderData.OutputNames + + def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: + return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() + + if names.RGBA in requested or names.RGB in requested: + buffers[names.RGBA] = _zeros(4, torch.uint8) + buffers[names.RGB] = buffers[names.RGBA][..., :3] + if names.ALBEDO in requested: + buffers[names.ALBEDO] = _zeros(4, torch.uint8) + if names.DEPTH in requested: + buffers[names.DEPTH] = _zeros(1, torch.float32) + if names.NORMALS in requested: + buffers[names.NORMALS] = _zeros(3, torch.float32) + if names.INSTANCE_SEGMENTATION in requested: + if self.cfg.colorize_instance_segmentation: + buffers[names.INSTANCE_SEGMENTATION] = _zeros(4, torch.uint8) + else: + buffers[names.INSTANCE_SEGMENTATION] = _zeros(1, torch.int32) + return buffers + def prepare_stage(self, stage: Any, num_envs: int) -> None: """No-op for Newton Warp - uses Newton scene directly without stage export. See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.prepare_stage`.""" diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer_cfg.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer_cfg.py index f6a5ce559af7..96db9ca41fd1 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer_cfg.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer_cfg.py @@ -33,3 +33,6 @@ class NewtonWarpRendererCfg(RendererCfg): create_default_light: bool = True """Create a default directional light source in the scene.""" + + colorize_instance_segmentation: bool = True + """Expose ``instance_segmentation_fast`` as ``(N, H, W, 4) uint8`` if True, else ``(N, H, W, 1) int32``.""" diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index bea88b77fa0b..5014c1cbff8e 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -63,34 +63,12 @@ class OVRTXRenderData: - """OVRTX-specific RenderData. Holds warp output buffers and weak ref to sensor. + """OVRTX-specific RenderData. Holds warp output buffers and a weakref to the sensor. - Follows Newton Warp pattern: weak ref to sensor avoids circular reference while - allowing access to sensor config when needed. + The sensor is stored as a weakref to avoid a Sensor ↔ RenderData reference cycle + (the sensor already owns this object). """ - @staticmethod - def _create_warp_buffers( - width: int, - height: int, - num_envs: int, - data_types: list[str], - device, - ) -> dict: - """Create warp output buffers for OVRTX renderer.""" - buffers = {} - if any(dt in ("rgba", "rgb") for dt in data_types): - buffers["rgba"] = wp.zeros((num_envs, height, width, 4), dtype=wp.uint8, device=device) - buffers["rgb"] = buffers["rgba"][:, :, :, :3] - if "albedo" in data_types: - buffers["albedo"] = wp.zeros((num_envs, height, width, 4), dtype=wp.uint8, device=device) - if "semantic_segmentation" in data_types: - buffers["semantic_segmentation"] = wp.zeros((num_envs, height, width, 4), dtype=wp.uint8, device=device) - for depth_key in ("depth", "distance_to_image_plane", "distance_to_camera"): - if depth_key in data_types: - buffers[depth_key] = wp.zeros((num_envs, height, width, 1), dtype=wp.float32, device=device) - return buffers - def __init__(self, sensor: SensorBase, device): """Create render data from sensor. Holds weak ref to avoid circular reference.""" self.sensor: weakref.ref[object] | None = weakref.ref(sensor) @@ -100,7 +78,7 @@ def __init__(self, sensor: SensorBase, device): self.data_types = sensor.cfg.data_types if sensor.cfg.data_types else ["rgb"] self.num_cols = math.ceil(math.sqrt(self.num_envs)) self.num_rows = math.ceil(self.num_envs / self.num_cols) - self.warp_buffers = self._create_warp_buffers(self.width, self.height, self.num_envs, self.data_types, device) + self.warp_buffers: dict[str, wp.array] = {} class OVRTXRenderer(BaseRenderer): @@ -112,6 +90,34 @@ class OVRTXRenderer(BaseRenderer): cfg: OVRTXRendererCfg + def create_output_buffers( + self, + data_types: list[str], + height: int, + width: int, + num_views: int, + device: torch.device | str, + ) -> dict[str, torch.Tensor]: + """Allocate output tensors for the data types OVRTX can produce. + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" + buffers: dict[str, torch.Tensor] = {} + requested = set(data_types) + + def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: + return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() + + if "rgba" in requested or "rgb" in requested: + buffers["rgba"] = _zeros(4, torch.uint8) + buffers["rgb"] = buffers["rgba"][..., :3] + if "albedo" in requested: + buffers["albedo"] = _zeros(4, torch.uint8) + if "semantic_segmentation" in requested: + buffers["semantic_segmentation"] = _zeros(4, torch.uint8) + for depth_key in ("depth", "distance_to_image_plane", "distance_to_camera"): + if depth_key in requested: + buffers[depth_key] = _zeros(1, torch.float32) + return buffers + def __init__(self, cfg: OVRTXRendererCfg): self.cfg = cfg self._usd_handles = [] @@ -333,9 +339,44 @@ def create_render_data(self, sensor: SensorBase) -> OVRTXRenderData: self.initialize(sensor) return OVRTXRenderData(sensor, DEVICE) - def set_outputs(self, render_data: OVRTXRenderData, output_data: dict) -> None: - """No-op; OVRTX uses internal warp buffers.""" - pass + # Map torch dtypes to their warp counterparts for zero-copy wrapping. + _TORCH_TO_WP_DTYPE: dict[torch.dtype, Any] = { + torch.uint8: wp.uint8, + torch.float32: wp.float32, + torch.int32: wp.int32, + } + + def set_outputs(self, render_data: OVRTXRenderData, output_data: dict[str, torch.Tensor]) -> None: + """Wrap caller-owned torch output tensors as zero-copy warp arrays. + + Aliased views over a contiguous sibling (e.g. ``rgb`` over ``rgba``) are + skipped; any other non-contiguous tensor raises ``ValueError``. + + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.set_outputs`. + """ + render_data.warp_buffers = {} + for name, tensor in output_data.items(): + if not tensor.is_contiguous(): + if tensor.data_ptr() in {t.data_ptr() for t in output_data.values() if t.is_contiguous()}: + continue + raise ValueError( + f"OVRTXRenderer.set_outputs: output '{name}' is non-contiguous and is not an" + " alias of a contiguous output tensor; cannot wrap as a zero-copy warp array." + ) + wp_dtype = self._TORCH_TO_WP_DTYPE.get(tensor.dtype) + if wp_dtype is None: + raise ValueError( + f"OVRTXRenderer.set_outputs: unsupported torch dtype {tensor.dtype} for output" + f" '{name}'. Add it to OVRTXRenderer._TORCH_TO_WP_DTYPE." + ) + torch_array = wp.from_torch(tensor) + render_data.warp_buffers[name] = wp.array( + ptr=torch_array.ptr, + dtype=wp_dtype, + shape=tuple(tensor.shape), + device=torch_array.device, + copy=False, + ) def update_transforms(self) -> None: """Sync physics objects to OVRTX.""" @@ -393,16 +434,15 @@ def read_output( render_data: OVRTXRenderData, camera_data: CameraData, ) -> None: - """Copy from render_data warp buffers to camera data output tensors.""" - for output_name in camera_data.output: - if output_name == "rgb": - continue - src = render_data.warp_buffers.get(output_name) - if src is None: - continue - output_data = camera_data.output[output_name] - if src.ptr != output_data.data_ptr(): - wp.copy(dest=wp.from_torch(output_data), src=src) + """No-op: outputs already live in the caller's torch storage. + + :meth:`set_outputs` wraps each ``camera_data.output`` tensor as a + zero-copy warp array stored in ``render_data.warp_buffers``, and + :meth:`render` writes the rendered tiles directly into those warp + arrays. There is therefore nothing to copy here. + + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.read_output`. + """ def _generate_random_colors_from_ids(self, input_ids: wp.array) -> wp.array: """Generate pseudo-random colors from semantic IDs.""" diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py index 5b07e3417ce0..e198cede3eb8 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py @@ -17,6 +17,9 @@ import numpy as np import torch import warp as wp +from packaging import version + +from pxr import Sdf from isaaclab.app.settings_manager import get_settings_manager from isaaclab.renderers import BaseRenderer @@ -72,6 +75,64 @@ class IsaacRtxRenderer(BaseRenderer): def __init__(self, cfg: IsaacRtxRendererCfg): self.cfg = cfg + # RTX rendering requires the app to be launched with ``--enable_cameras``. + if not get_settings_manager().get("/isaaclab/cameras_enabled"): + raise RuntimeError( + "A camera was spawned without the --enable_cameras flag. Please use --enable_cameras to enable" + " rendering." + ) + # ``/isaaclab/render/rtx_sensors`` is owned by ``Camera.__init__`` (must be set pre-``sim.reset()``). + + def create_output_buffers( + self, + data_types: list[str], + height: int, + width: int, + num_views: int, + device: torch.device | str, + ) -> dict[str, torch.Tensor]: + """Allocate Replicator-shaped output tensors for the data types Isaac RTX can produce. + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" + sim_major = get_isaac_sim_version().major + + buffers: dict[str, torch.Tensor] = {} + requested = set(data_types) + + def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: + return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() + + if "rgba" in requested or "rgb" in requested: + buffers["rgba"] = _zeros(4, torch.uint8) + # rgb shares storage with rgba (Replicator's native layout). + buffers["rgb"] = buffers["rgba"][..., :3] + if "albedo" in requested and sim_major >= 6: + buffers["albedo"] = _zeros(4, torch.uint8) + if sim_major >= 6: + for shading_type in SIMPLE_SHADING_MODES: + if shading_type in requested: + buffers[shading_type] = _zeros(3, torch.uint8) + for depth_key in ("depth", "distance_to_image_plane", "distance_to_camera"): + if depth_key in requested: + buffers[depth_key] = _zeros(1, torch.float32) + if "normals" in requested: + buffers["normals"] = _zeros(3, torch.float32) + if "motion_vectors" in requested: + buffers["motion_vectors"] = _zeros(2, torch.float32) + + seg_specs = ( + ("semantic_segmentation", self.cfg.colorize_semantic_segmentation), + ("instance_segmentation_fast", self.cfg.colorize_instance_segmentation), + ("instance_id_segmentation_fast", self.cfg.colorize_instance_id_segmentation), + ) + for name, colorize in seg_specs: + if name not in requested: + continue + if colorize: + buffers[name] = _zeros(4, torch.uint8) + else: + buffers[name] = _zeros(1, torch.int32) + + return buffers def prepare_stage(self, stage: Any, num_envs: int) -> None: """No-op for Isaac RTX - uses USD scene directly without export. @@ -105,6 +166,21 @@ def create_render_data(self, sensor: SensorBase) -> IsaacRtxRenderData: " The simple shading data types will be ignored." ) + # HACK: Isaac Sim 4.5 has a bug in Camera/TiledCamera that breaks segmentation + # outputs for instanceable assets. Disable instancing as a workaround. + if isaac_sim_version == version.parse("4.5") and ( + "semantic_segmentation" in sensor.cfg.data_types or "instance_segmentation_fast" in sensor.cfg.data_types + ): + logger.warning( + "Isaac Sim 4.5 introduced a bug in Camera and TiledCamera when outputting instance and semantic" + " segmentation outputs for instanceable assets. As a workaround, the instanceable flag on assets" + " will be disabled in the current workflow and may lead to longer load times and increased memory" + " usage." + ) + with Sdf.ChangeBlock(): + for prim in sensor.stage.Traverse(): + prim.SetInstanceable(False) + # Get camera prim paths from sensor view view = sensor._view cam_prim_paths = [] @@ -122,7 +198,7 @@ def create_render_data(self, sensor: SensorBase) -> IsaacRtxRenderData: # Synthetic-data instance mapping filter for segmentation; before annotator attach. SyntheticData.Get().set_instance_mapping_semantic_filter( - _camera_semantic_filter_predicate(sensor.cfg.semantic_filter) + _camera_semantic_filter_predicate(self.cfg.semantic_filter) ) # Register simple shading if needed @@ -169,13 +245,13 @@ def create_render_data(self, sensor: SensorBase) -> IsaacRtxRenderData: init_params = None if annotator_type == "semantic_segmentation": init_params = { - "colorize": sensor.cfg.colorize_semantic_segmentation, - "mapping": json.dumps(sensor.cfg.semantic_segmentation_mapping), + "colorize": self.cfg.colorize_semantic_segmentation, + "mapping": json.dumps(self.cfg.semantic_segmentation_mapping), } elif annotator_type == "instance_segmentation_fast": - init_params = {"colorize": sensor.cfg.colorize_instance_segmentation} + init_params = {"colorize": self.cfg.colorize_instance_segmentation} elif annotator_type == "instance_id_segmentation_fast": - init_params = {"colorize": sensor.cfg.colorize_instance_id_segmentation} + init_params = {"colorize": self.cfg.colorize_instance_id_segmentation} annotator = rep.AnnotatorRegistry.get_annotator( annotator_type, init_params, device=sensor.device, do_array_copy=False @@ -275,9 +351,9 @@ def tiling_grid_shape(): # Note: Replicator returns raw buffers of dtype uint32 for segmentation types # so we need to convert them to uint8 4 channel images for colorized types if ( - (data_type == "semantic_segmentation" and cfg.colorize_semantic_segmentation) - or (data_type == "instance_segmentation_fast" and cfg.colorize_instance_segmentation) - or (data_type == "instance_id_segmentation_fast" and cfg.colorize_instance_id_segmentation) + (data_type == "semantic_segmentation" and self.cfg.colorize_semantic_segmentation) + or (data_type == "instance_segmentation_fast" and self.cfg.colorize_instance_segmentation) + or (data_type == "instance_id_segmentation_fast" and self.cfg.colorize_instance_id_segmentation) ): tiled_data_buffer = wp.array( ptr=tiled_data_buffer.ptr, shape=(*tiled_data_buffer.shape, 4), dtype=wp.uint8, device=sensor.device @@ -321,10 +397,10 @@ def tiling_grid_shape(): # apply defined clipping behavior if ( data_type in ("distance_to_camera", "distance_to_image_plane", "depth") - and cfg.depth_clipping_behavior != "none" + and self.cfg.depth_clipping_behavior != "none" ): output_data[data_type][torch.isinf(output_data[data_type])] = ( - 0.0 if cfg.depth_clipping_behavior == "zero" else cfg.spawn.clipping_range[1] + 0.0 if self.cfg.depth_clipping_behavior == "zero" else cfg.spawn.clipping_range[1] ) def read_output(self, render_data: IsaacRtxRenderData, camera_data: CameraData) -> None: diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py index e36cca4e53b8..15043c6a2aa0 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py @@ -5,13 +5,88 @@ """Configuration for Isaac RTX (Replicator) Renderer.""" +from typing import Literal + from isaaclab.renderers.renderer_cfg import RendererCfg from isaaclab.utils import configclass @configclass class IsaacRtxRendererCfg(RendererCfg): - """Configuration for Isaac RTX renderer using Omniverse Replicator.""" + """Configuration for Isaac RTX renderer using Omniverse Replicator. + + Holds the Replicator/RTX-specific knobs (semantic segmentation, instance + segmentation, semantic filtering, depth clipping) used by the RTX rendering + pipeline. + """ renderer_type: str = "isaac_rtx" """Type identifier for Isaac RTX renderer.""" + + semantic_filter: str | list[str] = "*:*" + """A string or a list specifying a semantic filter predicate. Defaults to ``"*:*"``. + + If a string, it should be a disjunctive normal form of (semantic type, labels). For examples: + + * ``"typeA : labelA & !labelB | labelC , typeB: labelA ; typeC: labelE"``: + All prims with semantic type "typeA" and label "labelA" but not "labelB" or with label "labelC". + Also, all prims with semantic type "typeB" and label "labelA", or with semantic type "typeC" and label "labelE". + * ``"typeA : * ; * : labelA"``: All prims with semantic type "typeA" or with label "labelA" + + If a list of strings, each string should be a semantic type. The segmentation for prims with + semantics of the specified types will be retrieved. For example, if the list is ["class"], only + the segmentation for prims with semantics of type "class" will be retrieved. + + .. seealso:: + + For more information on the semantics filter, see the documentation on `Replicator Semantics Schema Editor`_. + + .. _Replicator Semantics Schema Editor: https://docs.omniverse.nvidia.com/extensions/latest/ext_replicator/semantics_schema_editor.html#semantics-filtering + """ + + colorize_semantic_segmentation: bool = True + """Whether to colorize the semantic segmentation images. Defaults to True. + + If True, semantic segmentation is converted to an image where semantic IDs are mapped to colors + and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + """ + + colorize_instance_id_segmentation: bool = True + """Whether to colorize the instance ID segmentation images. Defaults to True. + + If True, instance id segmentation is converted to an image where instance IDs are mapped to colors. + and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + """ + + colorize_instance_segmentation: bool = True + """Whether to colorize the instance ID segmentation images. Defaults to True. + + If True, instance segmentation is converted to an image where instance IDs are mapped to colors. + and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. + """ + + semantic_segmentation_mapping: dict = {} + """Dictionary mapping semantics to specific colours + + Eg. + + .. code-block:: python + + { + "class:cube_1": (255, 36, 66, 255), + "class:cube_2": (255, 184, 48, 255), + "class:cube_3": (55, 255, 139, 255), + "class:table": (255, 237, 218, 255), + "class:ground": (100, 100, 100, 255), + "class:robot": (61, 178, 255, 255), + } + + """ + + depth_clipping_behavior: Literal["max", "zero", "none"] = "none" + """Clipping behavior for the camera for values exceed the maximum value. Defaults to "none". + + - ``"max"``: Values are clipped to the maximum value. + - ``"zero"``: Values are clipped to zero. + - ``"none``: No clipping is applied. Values will be returned as ``inf``. + """ From 56fee8dee847434d7eedbe5da2e51c864a66a572 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 23 Apr 2026 10:32:12 -0700 Subject: [PATCH 2/7] Reset values to default to avoid re-forward --- source/isaaclab/isaaclab/sensors/camera/camera_cfg.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index 6ac34f533bb9..2cd92a8ba3ac 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -214,3 +214,6 @@ def __post_init__(self): ) if hasattr(self.renderer_cfg, field_name): setattr(self.renderer_cfg, field_name, value) + # Reset to default so re-runs of ``__post_init__`` (via ``SensorBase.__init__``'s + # ``cfg.copy()``) don't re-forward and clobber a user-set ``renderer_cfg`` field. + setattr(self, field_name, default) From 16d631a2a9e11c38f4860107a1cc2e57d4cee1fd Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 23 Apr 2026 11:35:44 -0700 Subject: [PATCH 3/7] Update tests and changelog --- docs/source/how-to/save_camera_output.rst | 8 +- .../tutorials/04_sensors/run_usd_camera.py | 15 +- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 27 +++ .../isaaclab/sensors/camera/camera_cfg.py | 12 +- .../renderers/test_create_output_buffers.py | 213 ++++++++++++++++++ source/isaaclab/test/sensors/test_camera.py | 86 +++++++ 7 files changed, 349 insertions(+), 14 deletions(-) create mode 100644 source/isaaclab/test/renderers/test_create_output_buffers.py diff --git a/docs/source/how-to/save_camera_output.rst b/docs/source/how-to/save_camera_output.rst index 1c050afaa17d..01b404efc0d8 100644 --- a/docs/source/how-to/save_camera_output.rst +++ b/docs/source/how-to/save_camera_output.rst @@ -14,7 +14,7 @@ directory. .. literalinclude:: ../../../scripts/tutorials/04_sensors/run_usd_camera.py :language: python - :emphasize-lines: 171-179, 229-247, 251-264 + :emphasize-lines: 174-182, 232-250, 254-267 :linenos: @@ -25,6 +25,12 @@ Saving using Replicator Basic Writer The BasicWriter is part of the Omniverse Replicator ecosystem and is specific to the default Isaac RTX renderer backend. Other renderer backends may require different save workflows. +.. note:: + The ``colorize_*`` arguments below are set on + :attr:`~isaaclab.sensors.camera.CameraCfg.renderer_cfg` (an + :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg`); the same-named + fields on :class:`~isaaclab.sensors.camera.CameraCfg` are deprecated. + To save camera outputs, we use the basic write class from Omniverse Replicator. This class allows us to save the images in a numpy format. For more information on the basic writer, please check the `documentation `_. diff --git a/scripts/tutorials/04_sensors/run_usd_camera.py b/scripts/tutorials/04_sensors/run_usd_camera.py index 547190643301..5c041d737c5d 100644 --- a/scripts/tutorials/04_sensors/run_usd_camera.py +++ b/scripts/tutorials/04_sensors/run_usd_camera.py @@ -65,6 +65,7 @@ import numpy as np import torch +from isaaclab_physx.renderers import IsaacRtxRendererCfg import omni.replicator.core as rep @@ -97,9 +98,11 @@ def define_sensor() -> Camera: "instance_segmentation_fast", "instance_id_segmentation_fast", ], - colorize_semantic_segmentation=True, - colorize_instance_id_segmentation=True, - colorize_instance_segmentation=True, + renderer_cfg=IsaacRtxRendererCfg( + colorize_semantic_segmentation=True, + colorize_instance_id_segmentation=True, + colorize_instance_segmentation=True, + ), spawn=sim_utils.PinholeCameraCfg( focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5) ), @@ -173,9 +176,9 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): rep_writer = rep.BasicWriter( output_dir=output_dir, frame_padding=0, - colorize_instance_id_segmentation=camera.cfg.colorize_instance_id_segmentation, - colorize_instance_segmentation=camera.cfg.colorize_instance_segmentation, - colorize_semantic_segmentation=camera.cfg.colorize_semantic_segmentation, + colorize_instance_id_segmentation=camera.cfg.renderer_cfg.colorize_instance_id_segmentation, + colorize_instance_segmentation=camera.cfg.renderer_cfg.colorize_instance_segmentation, + colorize_semantic_segmentation=camera.cfg.renderer_cfg.colorize_semantic_segmentation, ) # Camera positions, targets, orientations diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 3086a2b93c88..fad2b53b6c5e 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.6.12" +version = "4.6.13" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index d5af850f2412..1631a9fcbf4c 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,33 @@ Changelog --------- +4.6.13 (2026-04-23) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Renderer backends now own output-buffer allocation via a new + ``BaseRenderer.create_output_buffers`` hook. Backends are the source of truth + for shape, dtype, and any aliasing (e.g. ``rgb`` as a view into ``rgba``). + Requested data types the backend cannot produce are dropped with a single + warning, instead of being silently discarded later. +* :class:`~isaaclab_ov.renderers.OVRTXRenderer` now writes rendered tiles + directly into the torch storage backing ``camera.data.output``, eliminating + the per-frame ``wp.copy`` bridge. +* Moved Kit/RTX-only logic out of :class:`~isaaclab.sensors.camera.Camera` + into :class:`~isaaclab_physx.renderers.IsaacRtxRenderer`. + +Deprecated +^^^^^^^^^^ + +* Deprecated RTX-flavored fields on :class:`~isaaclab.sensors.camera.CameraCfg` + (``semantic_filter``, ``colorize_semantic_segmentation``, + ``colorize_instance_segmentation``, ``colorize_instance_id_segmentation``, + ``semantic_segmentation_mapping``, ``depth_clipping_behavior``); set them on + :attr:`~isaaclab.sensors.camera.CameraCfg.renderer_cfg` instead. + + 4.6.12 (2026-04-23) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index 2cd92a8ba3ac..658937176c1d 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -81,7 +81,7 @@ class OffsetCfg: - ``"zero"``: Values are clipped to zero. - ``"none``: No clipping is applied. Values will be returned as ``inf``. - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.depth_clipping_behavior` on :attr:`renderer_cfg` instead. @@ -127,7 +127,7 @@ class OffsetCfg: .. _Replicator Semantics Schema Editor: https://docs.omniverse.nvidia.com/extensions/latest/ext_replicator/semantics_schema_editor.html#semantics-filtering - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.semantic_filter` on :attr:`renderer_cfg` instead. @@ -139,7 +139,7 @@ class OffsetCfg: If True, semantic segmentation is converted to an image where semantic IDs are mapped to colors and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_semantic_segmentation` on :attr:`renderer_cfg` instead. @@ -151,7 +151,7 @@ class OffsetCfg: If True, instance id segmentation is converted to an image where instance IDs are mapped to colors. and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_instance_id_segmentation` on :attr:`renderer_cfg` instead. @@ -163,7 +163,7 @@ class OffsetCfg: If True, instance segmentation is converted to an image where instance IDs are mapped to colors. and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.colorize_instance_segmentation` on :attr:`renderer_cfg` instead. @@ -185,7 +185,7 @@ class OffsetCfg: "class:robot": (61, 178, 255, 255), } - .. deprecated:: 4.7.0 + .. deprecated:: 4.6.13 This field is RTX-specific. Set :attr:`~isaaclab_physx.renderers.IsaacRtxRendererCfg.semantic_segmentation_mapping` on :attr:`renderer_cfg` instead. diff --git a/source/isaaclab/test/renderers/test_create_output_buffers.py b/source/isaaclab/test/renderers/test_create_output_buffers.py new file mode 100644 index 000000000000..700cf71dfeb0 --- /dev/null +++ b/source/isaaclab/test/renderers/test_create_output_buffers.py @@ -0,0 +1,213 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for the renderer-owned output buffers contract and CameraCfg deprecation forwarding.""" + +import warnings + +import pytest +import torch + +pytest.importorskip("isaaclab_physx") + +from isaaclab.sensors.camera import CameraCfg, TiledCameraCfg +from isaaclab.sim import PinholeCameraCfg +from isaaclab_physx.renderers import IsaacRtxRendererCfg + +_SPAWN = PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), +) + + +# ----------------------------------------------------------------------------- +# CameraCfg deprecation forwarding +# ----------------------------------------------------------------------------- + + +@pytest.mark.parametrize( + "field_name,deprecated_value", + [ + ("colorize_semantic_segmentation", False), + ("colorize_instance_segmentation", False), + ("colorize_instance_id_segmentation", False), + ("semantic_filter", ["class"]), + ("semantic_segmentation_mapping", {"class:cube": (1, 2, 3, 4)}), + ("depth_clipping_behavior", "max"), + ], +) +def test_camera_cfg_forwards_deprecated_fields_to_renderer_cfg(field_name, deprecated_value): + """Deprecated RTX-flavored field set on CameraCfg lands on renderer_cfg and warns.""" + kwargs = { + "height": 64, + "width": 64, + "prim_path": "/World/Camera", + "spawn": _SPAWN, + "data_types": ["rgb"], + field_name: deprecated_value, + } + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = CameraCfg(**kwargs) + + deprecation_warnings = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert any(f"CameraCfg.{field_name}" in str(w.message) for w in deprecation_warnings) + assert getattr(cfg.renderer_cfg, field_name) == deprecated_value + + +def test_camera_cfg_default_does_not_warn_or_forward(): + """Default-valued deprecated fields stay silent.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = CameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + ) + + deprecation_warnings = [ + w for w in caught + if issubclass(w.category, DeprecationWarning) and "CameraCfg." in str(w.message) + ] + assert deprecation_warnings == [] + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +def test_camera_cfg_post_construction_mutation_is_silent_no_op(): + """Mutating a deprecated field after construction does not propagate to renderer_cfg.""" + cfg = CameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + ) + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + cfg.colorize_semantic_segmentation = False + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): + """TiledCameraCfg skips CameraCfg's per-field forwarder by design.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = TiledCameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + colorize_semantic_segmentation=False, + ) + + tiled_warnings = [ + w for w in caught + if issubclass(w.category, DeprecationWarning) and "TiledCameraCfg" in str(w.message) + ] + assert tiled_warnings + + field_warnings = [ + w for w in caught + if issubclass(w.category, DeprecationWarning) and "CameraCfg.colorize_" in str(w.message) + ] + assert field_warnings == [] + + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +# ----------------------------------------------------------------------------- +# IsaacRtxRenderer.create_output_buffers contract +# ----------------------------------------------------------------------------- + + +def test_isaac_rtx_create_output_buffers_omits_unsupported_and_aliases_rgb(): + """RTX backend drops names it cannot produce; rgb aliases rgba storage.""" + pytest.importorskip("pxr") + pytest.importorskip("isaacsim.core") + from isaaclab_physx.renderers.isaac_rtx_renderer import IsaacRtxRenderer + + renderer = IsaacRtxRenderer.__new__(IsaacRtxRenderer) + renderer.cfg = IsaacRtxRendererCfg() + + requested = ["rgb", "rgba", "depth", "definitely_not_supported"] + buffers = renderer.create_output_buffers( + data_types=requested, height=8, width=16, num_views=2, device="cpu" + ) + + assert "definitely_not_supported" not in buffers + assert {"rgb", "rgba", "depth"} <= set(buffers.keys()) + assert buffers["rgba"].shape == (2, 8, 16, 4) + assert buffers["rgba"].dtype == torch.uint8 + assert buffers["depth"].shape == (2, 8, 16, 1) + assert buffers["depth"].dtype == torch.float32 + assert buffers["rgb"].data_ptr() == buffers["rgba"].data_ptr() + + +# ----------------------------------------------------------------------------- +# OVRTX zero-copy consolidation +# ----------------------------------------------------------------------------- + + +def _make_ovrtx_render_data(): + """Construct a minimal OVRTXRenderData without invoking its sensor-based __init__.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderData + + rd = OVRTXRenderData.__new__(OVRTXRenderData) + rd.warp_buffers = {} + return rd + + +def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): + """OVRTXRenderer.set_outputs publishes warp views over the caller's torch storage.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + import warp as wp + + from isaaclab_ov.renderers import OVRTXRendererCfg + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + + if not torch.cuda.is_available(): + pytest.skip("OVRTX zero-copy wrapping requires a CUDA device") + device = "cuda" + + buffers = renderer.create_output_buffers( + data_types=["rgb", "rgba", "depth"], height=8, width=16, num_views=2, device=device + ) + render_data = _make_ovrtx_render_data() + renderer.set_outputs(render_data, buffers) + + assert set(render_data.warp_buffers.keys()) >= {"rgba", "depth"} + assert render_data.warp_buffers["rgba"].ptr == wp.from_torch(buffers["rgba"]).ptr + assert render_data.warp_buffers["depth"].ptr == wp.from_torch(buffers["depth"]).ptr + assert "rgb" not in render_data.warp_buffers + + +def test_ovrtx_read_output_is_a_no_op_after_consolidation(): + """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + from isaaclab.sensors.camera.camera_data import CameraData + from isaaclab_ov.renderers import OVRTXRendererCfg + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + render_data = _make_ovrtx_render_data() + camera_data = CameraData() + camera_data.info = {} + camera_data.output = {} + + result = renderer.read_output(render_data, camera_data) + assert result is None + assert render_data.warp_buffers == {} + assert camera_data.info == {} + assert camera_data.output == {} diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 926492450ed0..c912c72a44fb 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -1080,6 +1080,92 @@ def test_camera_frame_offset(setup_camera_device, device): del camera +def test_camera_warns_once_on_unsupported_data_types(setup_sim_camera, caplog): + """Test Camera warns once and drops data types its renderer cannot produce.""" + import logging + + from isaaclab.renderers import Renderer + from isaaclab.renderers.base_renderer import BaseRenderer + + sim, camera_cfg, dt = setup_sim_camera + camera_cfg = copy.deepcopy(camera_cfg) + camera_cfg.data_types = ["rgba", "depth", "normals"] + + class _PartialRenderer(BaseRenderer): + """Returns only ``rgba`` regardless of what was asked for.""" + + def __init__(self, cfg=None): + self.cfg = cfg + + def create_output_buffers(self, data_types, height, width, num_views, device): + buffers: dict[str, torch.Tensor] = {} + if "rgba" in data_types or "rgb" in data_types: + buffers["rgba"] = torch.zeros((num_views, height, width, 4), dtype=torch.uint8, device=device) + return buffers + + def prepare_stage(self, stage, num_envs): + pass + + def create_render_data(self, sensor): + return object() + + def set_outputs(self, render_data, output_data): + pass + + def update_transforms(self): + pass + + def update_camera(self, render_data, positions, orientations, intrinsics): + pass + + def render(self, render_data): + pass + + def read_output(self, render_data, camera_data): + pass + + def cleanup(self, render_data): + pass + + backend = Renderer._get_backend(camera_cfg.renderer_cfg) + original = Renderer._registry.get(backend) + Renderer._registry[backend] = _PartialRenderer + try: + camera = Camera(camera_cfg) + caplog.clear() + with caplog.at_level(logging.WARNING, logger="isaaclab.sensors.camera.camera"): + sim.reset() + # Step a few frames and confirm the warning is emitted once at init. + for _ in range(3): + sim.step() + camera.update(dt) + + warning_records = [ + r for r in caplog.records if r.levelno == logging.WARNING and "does not support" in r.getMessage() + ] + assert len(warning_records) == 1, ( + f"Expected exactly one 'does not support' warning, got {len(warning_records)}:" + f" {[r.getMessage() for r in warning_records]}" + ) + msg = warning_records[0].getMessage() + assert "_PartialRenderer" in msg + assert "depth" in msg + assert "normals" in msg + assert "rgba" not in msg + + # Only the supported subset is in ``data.output``; the rest were dropped. + assert set(camera.data.output.keys()) == {"rgba"} + # ``data.info`` mirrors the ``data.output`` keys. + assert set(camera.data.info.keys()) == {"rgba"} + + del camera + finally: + if original is not None: + Renderer._registry[backend] = original + else: + Renderer._registry.pop(backend, None) + + def _populate_scene(): """Add prims to the scene.""" # Ground-plane From 404d79f74b98ec04314c87aa21b1ccfd0c1e86ae Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 23 Apr 2026 11:45:14 -0700 Subject: [PATCH 4/7] Formatting --- .../renderers/test_create_output_buffers.py | 20 ++++++++----------- 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/source/isaaclab/test/renderers/test_create_output_buffers.py b/source/isaaclab/test/renderers/test_create_output_buffers.py index 700cf71dfeb0..7e7a375b38b6 100644 --- a/source/isaaclab/test/renderers/test_create_output_buffers.py +++ b/source/isaaclab/test/renderers/test_create_output_buffers.py @@ -12,9 +12,10 @@ pytest.importorskip("isaaclab_physx") +from isaaclab_physx.renderers import IsaacRtxRendererCfg + from isaaclab.sensors.camera import CameraCfg, TiledCameraCfg from isaaclab.sim import PinholeCameraCfg -from isaaclab_physx.renderers import IsaacRtxRendererCfg _SPAWN = PinholeCameraCfg( focal_length=24.0, @@ -72,8 +73,7 @@ def test_camera_cfg_default_does_not_warn_or_forward(): ) deprecation_warnings = [ - w for w in caught - if issubclass(w.category, DeprecationWarning) and "CameraCfg." in str(w.message) + w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg." in str(w.message) ] assert deprecation_warnings == [] assert cfg.renderer_cfg.colorize_semantic_segmentation is True @@ -107,14 +107,12 @@ def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): ) tiled_warnings = [ - w for w in caught - if issubclass(w.category, DeprecationWarning) and "TiledCameraCfg" in str(w.message) + w for w in caught if issubclass(w.category, DeprecationWarning) and "TiledCameraCfg" in str(w.message) ] assert tiled_warnings field_warnings = [ - w for w in caught - if issubclass(w.category, DeprecationWarning) and "CameraCfg.colorize_" in str(w.message) + w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg.colorize_" in str(w.message) ] assert field_warnings == [] @@ -136,9 +134,7 @@ def test_isaac_rtx_create_output_buffers_omits_unsupported_and_aliases_rgb(): renderer.cfg = IsaacRtxRendererCfg() requested = ["rgb", "rgba", "depth", "definitely_not_supported"] - buffers = renderer.create_output_buffers( - data_types=requested, height=8, width=16, num_views=2, device="cpu" - ) + buffers = renderer.create_output_buffers(data_types=requested, height=8, width=16, num_views=2, device="cpu") assert "definitely_not_supported" not in buffers assert {"rgb", "rgba", "depth"} <= set(buffers.keys()) @@ -170,7 +166,6 @@ def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): pytest.importorskip("isaaclab_ov") pytest.importorskip("ovrtx") import warp as wp - from isaaclab_ov.renderers import OVRTXRendererCfg from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer @@ -196,10 +191,11 @@ def test_ovrtx_read_output_is_a_no_op_after_consolidation(): """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" pytest.importorskip("isaaclab_ov") pytest.importorskip("ovrtx") - from isaaclab.sensors.camera.camera_data import CameraData from isaaclab_ov.renderers import OVRTXRendererCfg from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + from isaaclab.sensors.camera.camera_data import CameraData + renderer = OVRTXRenderer(OVRTXRendererCfg()) render_data = _make_ovrtx_render_data() camera_data = CameraData() From 9cb99db29c5ae62d67866953e9882e28a99c6cf1 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 23 Apr 2026 17:57:24 -0700 Subject: [PATCH 5/7] Common output types contract --- .../isaaclab/isaaclab/renderers/__init__.pyi | 3 + .../isaaclab/renderers/base_renderer.py | 26 +- .../isaaclab/renderers/output_contract.py | 54 +++ source/isaaclab/isaaclab/sensors/__init__.pyi | 4 + .../isaaclab/sensors/camera/__init__.pyi | 4 +- .../isaaclab/sensors/camera/camera.py | 53 ++- .../isaaclab/sensors/camera/camera_data.py | 82 ++++ .../renderers/test_camera_output_contract.py | 411 ++++++++++++++++++ .../renderers/test_create_output_buffers.py | 209 --------- .../test/renderers/test_renderer_factory.py | 2 +- source/isaaclab/test/sensors/test_camera.py | 11 +- .../renderers/newton_warp_renderer.py | 77 ++-- .../isaaclab_ov/renderers/ovrtx_renderer.py | 41 +- .../renderers/isaac_rtx_renderer.py | 68 ++- 14 files changed, 665 insertions(+), 380 deletions(-) create mode 100644 source/isaaclab/isaaclab/renderers/output_contract.py create mode 100644 source/isaaclab/test/renderers/test_camera_output_contract.py delete mode 100644 source/isaaclab/test/renderers/test_create_output_buffers.py diff --git a/source/isaaclab/isaaclab/renderers/__init__.pyi b/source/isaaclab/isaaclab/renderers/__init__.pyi index e6785bd0e090..34d592036526 100644 --- a/source/isaaclab/isaaclab/renderers/__init__.pyi +++ b/source/isaaclab/isaaclab/renderers/__init__.pyi @@ -5,10 +5,13 @@ __all__ = [ "BaseRenderer", + "CameraDataType", + "OutputSpec", "Renderer", "RendererCfg", ] from .base_renderer import BaseRenderer +from .output_contract import CameraDataType, OutputSpec from .renderer import Renderer from .renderer_cfg import RendererCfg diff --git a/source/isaaclab/isaaclab/renderers/base_renderer.py b/source/isaaclab/isaaclab/renderers/base_renderer.py index 900ef80ffdb7..5706c7d3ee8d 100644 --- a/source/isaaclab/isaaclab/renderers/base_renderer.py +++ b/source/isaaclab/isaaclab/renderers/base_renderer.py @@ -10,6 +10,8 @@ from abc import ABC, abstractmethod from typing import TYPE_CHECKING, Any +from .output_contract import CameraDataType, OutputSpec + if TYPE_CHECKING: import torch @@ -21,29 +23,13 @@ class BaseRenderer(ABC): """Abstract base class for renderer implementations.""" @abstractmethod - def create_output_buffers( - self, - data_types: list[str], - height: int, - width: int, - num_views: int, - device: torch.device | str, - ) -> dict[str, torch.Tensor]: - """Allocate output tensors for the supported subset of ``data_types``. - - Implementations MUST omit any data-type names they cannot produce and - allocate on ``device``. They MAY include aliased entries that share - storage with another entry (e.g. ``rgb`` as a view into ``rgba``). + def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + """Per-output layout (channels + dtype) this renderer can produce. - Args: - data_types: Names of the requested data types. - height: Image height in pixels. - width: Image width in pixels. - num_views: Number of camera views (batch dimension). - device: Torch device on which to allocate the buffers. + Outputs absent from the mapping are not produced by this backend. Returns: - Mapping from data-type name to a pre-allocated tensor. + Mapping from supported :class:`CameraDataType` to its :class:`OutputSpec`. """ pass diff --git a/source/isaaclab/isaaclab/renderers/output_contract.py b/source/isaaclab/isaaclab/renderers/output_contract.py new file mode 100644 index 000000000000..713fcf1c78e7 --- /dev/null +++ b/source/isaaclab/isaaclab/renderers/output_contract.py @@ -0,0 +1,54 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Renderer→consumer output contract types. + +Leaf module shared by :class:`~isaaclab.renderers.BaseRenderer` and +:class:`~isaaclab.sensors.camera.CameraData` to avoid a direct dependency +between them. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from enum import StrEnum +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + import torch + + +class CameraDataType(StrEnum): + """Canonical names for the per-pixel data types a renderer can publish. + + String values match the vocabulary used by + :attr:`isaaclab.sensors.camera.CameraCfg.data_types`. + """ + + RGB = "rgb" + RGBA = "rgba" + ALBEDO = "albedo" + DEPTH = "depth" + DISTANCE_TO_IMAGE_PLANE = "distance_to_image_plane" + DISTANCE_TO_CAMERA = "distance_to_camera" + NORMALS = "normals" + MOTION_VECTORS = "motion_vectors" + SEMANTIC_SEGMENTATION = "semantic_segmentation" + INSTANCE_SEGMENTATION_FAST = "instance_segmentation_fast" + INSTANCE_ID_SEGMENTATION_FAST = "instance_id_segmentation_fast" + SIMPLE_SHADING_CONSTANT_DIFFUSE = "simple_shading_constant_diffuse" + SIMPLE_SHADING_DIFFUSE_MDL = "simple_shading_diffuse_mdl" + SIMPLE_SHADING_FULL_MDL = "simple_shading_full_mdl" + + +@dataclass(frozen=True) +class OutputSpec: + """Per-pixel layout (channels + dtype) for one renderer output type.""" + + channels: int + """Number of per-pixel channels (last dimension of the allocated tensor).""" + + dtype: torch.dtype + """Torch dtype the renderer writes for this output type.""" diff --git a/source/isaaclab/isaaclab/sensors/__init__.pyi b/source/isaaclab/isaaclab/sensors/__init__.pyi index 374dace85427..36471f3bf2ee 100644 --- a/source/isaaclab/isaaclab/sensors/__init__.pyi +++ b/source/isaaclab/isaaclab/sensors/__init__.pyi @@ -9,6 +9,8 @@ __all__ = [ "Camera", "CameraCfg", "CameraData", + "CameraDataType", + "OutputSpec", "TiledCamera", "TiledCameraCfg", "transform_points", @@ -56,6 +58,8 @@ from .camera import ( Camera, CameraCfg, CameraData, + CameraDataType, + OutputSpec, TiledCamera, TiledCameraCfg, transform_points, diff --git a/source/isaaclab/isaaclab/sensors/camera/__init__.pyi b/source/isaaclab/isaaclab/sensors/camera/__init__.pyi index 0bdc3fb85261..3b5873d19bc8 100644 --- a/source/isaaclab/isaaclab/sensors/camera/__init__.pyi +++ b/source/isaaclab/isaaclab/sensors/camera/__init__.pyi @@ -7,6 +7,8 @@ __all__ = [ "Camera", "CameraCfg", "CameraData", + "CameraDataType", + "OutputSpec", "TiledCamera", "TiledCameraCfg", "transform_points", @@ -17,7 +19,7 @@ __all__ = [ from .camera import Camera from .camera_cfg import CameraCfg -from .camera_data import CameraData +from .camera_data import CameraData, CameraDataType, OutputSpec from .tiled_camera import TiledCamera from .tiled_camera_cfg import TiledCameraCfg from .utils import ( diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index ee82cb0bee0b..32f3fae0bdd0 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -27,7 +27,7 @@ ) from ..sensor_base import SensorBase -from .camera_data import CameraData +from .camera_data import CameraData, CameraDataType if TYPE_CHECKING: from .camera_cfg import CameraCfg @@ -129,8 +129,8 @@ def __init__(self, cfg: CameraCfg): # UsdGeom Camera prim for the sensor self._sensor_prims: list[UsdGeom.Camera] = list() - # Create empty variables for storing output data - self._data = CameraData() + # Allocated in :meth:`_create_buffers` once the renderer's output contract is known. + self._data: CameraData | None = None # Renderer and render data — assigned in _initialize_impl. self._renderer: BaseRenderer | None = None self._render_data = None @@ -448,32 +448,39 @@ def _check_supported_data_types(self, cfg: CameraCfg): def _create_buffers(self): """Create buffers for storing data.""" - # -- intrinsic matrix - self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device) - self._update_intrinsic_matrices(self._ALL_INDICES) - # -- pose of the cameras - self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device) - self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device) - self._update_poses(self._ALL_INDICES) - self._data.image_shape = self.image_shape - # -- output data: ask the renderer to allocate buffers for the requested data types. - buffers = self._renderer.create_output_buffers( - self.cfg.data_types, - self.cfg.height, - self.cfg.width, - self._view.count, - self.device, - ) - # Surface any requested data types the active renderer cannot produce. - unsupported = [name for name in self.cfg.data_types if name not in buffers] + specs = self._renderer.supported_output_types() + # Split requested names into known/unsupported; warn once for any the renderer can't produce. + known: list[str] = [] + unsupported: list[str] = [] + for name in self.cfg.data_types: + try: + if CameraDataType(name) in specs: + known.append(name) + else: + unsupported.append(name) + except ValueError: + unsupported.append(name) if unsupported: logger.warning( "Renderer %s does not support the following requested data types and will not produce them: %s", type(self._renderer).__name__, unsupported, ) - self._data.output = buffers - self._data.info = {name: None for name in buffers} + self._data = CameraData.allocate( + data_types=known, + height=self.cfg.height, + width=self.cfg.width, + num_views=self._view.count, + device=self._device, + supported_specs=specs, + ) + # Camera-frame state (pose / intrinsics) is owned by the camera, not + # the renderer: populate it on the freshly constructed ``CameraData``. + self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device) + self._update_intrinsic_matrices(self._ALL_INDICES) + self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device) + self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device) + self._update_poses(self._ALL_INDICES) self._renderer.set_outputs(self._render_data, self._data.output) def _update_intrinsic_matrices(self, env_ids: Sequence[int]): diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_data.py b/source/isaaclab/isaaclab/sensors/camera/camera_data.py index 6c9ce29bcc7d..40f78660ff61 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_data.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_data.py @@ -3,13 +3,19 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import dataclass from typing import Any import torch +# Re-exported as part of the public isaaclab.sensors.camera API +from isaaclab.renderers.output_contract import CameraDataType, OutputSpec from isaaclab.utils.math import convert_camera_frame_orientation_convention +__all__ = ["CameraData", "CameraDataType", "OutputSpec"] + @dataclass class CameraData: @@ -64,6 +70,82 @@ class CameraData: types, the info is empty. """ + @classmethod + def allocate( + cls, + data_types: list[str], + height: int, + width: int, + num_views: int, + device: torch.device | str, + supported_specs: dict[CameraDataType, OutputSpec], + ) -> CameraData: + """Build a :class:`CameraData` with output buffers pre-allocated. + + Allocates one ``(num_views, height, width, channels)`` tensor per type + in the intersection of ``data_types`` and ``supported_specs``, using + the channels and dtype from each :class:`OutputSpec`. + + Args: + data_types: Requested output names (typically :attr:`CameraCfg.data_types`). + Every name must be a member of :class:`CameraDataType`. + height: Image height in pixels. + width: Image width in pixels. + num_views: Number of camera views (batch dimension). + device: Torch device on which to allocate the buffers. + supported_specs: Per-output layout the active renderer can produce, + keyed by :class:`CameraDataType`. Names absent from this mapping + are not allocated. + + Returns: + A new :class:`CameraData` with :attr:`image_shape`, :attr:`output`, + and :attr:`info` populated; all other fields at their defaults. + + Raises: + ValueError: If ``data_types`` contains names that are not members of + :class:`CameraDataType`. + """ + requested: set[CameraDataType] = set() + unknown: list[str] = [] + for name in data_types: + try: + requested.add(CameraDataType(name)) + except ValueError: + unknown.append(name) + if unknown: + raise ValueError( + f"Unknown CameraDataType name(s): {unknown}. Expected members of CameraDataType." + ) + # rgb is exposed as a view into rgba when the renderer publishes both, + # so requesting either one allocates the shared rgba buffer. + rgb_alias = ( + CameraDataType.RGBA in supported_specs + and CameraDataType.RGB in supported_specs + and (CameraDataType.RGB in requested or CameraDataType.RGBA in requested) + ) + if rgb_alias: + requested.update({CameraDataType.RGB, CameraDataType.RGBA}) + + buffers: dict[str, torch.Tensor] = {} + for name, spec in supported_specs.items(): + if name not in requested: + continue + if rgb_alias and name == CameraDataType.RGB: + continue + buffers[str(name)] = torch.zeros( + (num_views, height, width, spec.channels), + dtype=spec.dtype, + device=device, + ).contiguous() + if rgb_alias: + buffers[str(CameraDataType.RGB)] = buffers[str(CameraDataType.RGBA)][..., :3] + + return cls( + image_shape=(height, width), + output=buffers, + info={name: None for name in buffers}, + ) + ## # Additional Frame orientation conventions ## diff --git a/source/isaaclab/test/renderers/test_camera_output_contract.py b/source/isaaclab/test/renderers/test_camera_output_contract.py new file mode 100644 index 000000000000..2254d8ae55cb --- /dev/null +++ b/source/isaaclab/test/renderers/test_camera_output_contract.py @@ -0,0 +1,411 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for the renderer→camera output contract. + +The renderer publishes the per-output layout via +:meth:`isaaclab.renderers.BaseRenderer.supported_output_types`; ``CameraData`` +allocates storage for the supported subset of the requested types and aliases +``rgb`` into ``rgba``. These tests cover both halves of that contract plus +:class:`CameraCfg` deprecation forwarding (which feeds the renderer cfg the +contract is published from). +""" + +import warnings +from unittest.mock import patch + +import pytest +import torch + +pytest.importorskip("isaaclab_physx") + +from isaaclab_physx.renderers import IsaacRtxRendererCfg + +from isaaclab.sensors.camera import CameraCfg, TiledCameraCfg +from isaaclab.sensors.camera.camera_data import CameraData, CameraDataType, OutputSpec +from isaaclab.sim import PinholeCameraCfg + +_SPAWN = PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), +) + + +# ----------------------------------------------------------------------------- +# CameraCfg deprecation forwarding +# ----------------------------------------------------------------------------- + + +@pytest.mark.parametrize( + "field_name,deprecated_value", + [ + ("colorize_semantic_segmentation", False), + ("colorize_instance_segmentation", False), + ("colorize_instance_id_segmentation", False), + ("semantic_filter", ["class"]), + ("semantic_segmentation_mapping", {"class:cube": (1, 2, 3, 4)}), + ("depth_clipping_behavior", "max"), + ], +) +def test_camera_cfg_forwards_deprecated_fields_to_renderer_cfg(field_name, deprecated_value): + """Deprecated RTX-flavored field set on CameraCfg lands on renderer_cfg and warns.""" + kwargs = { + "height": 64, + "width": 64, + "prim_path": "/World/Camera", + "spawn": _SPAWN, + "data_types": ["rgb"], + field_name: deprecated_value, + } + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = CameraCfg(**kwargs) + + deprecation_warnings = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert any(f"CameraCfg.{field_name}" in str(w.message) for w in deprecation_warnings) + assert getattr(cfg.renderer_cfg, field_name) == deprecated_value + + +def test_camera_cfg_default_does_not_warn_or_forward(): + """Default-valued deprecated fields stay silent.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = CameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + ) + + deprecation_warnings = [ + w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg." in str(w.message) + ] + assert deprecation_warnings == [] + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +def test_camera_cfg_post_construction_mutation_is_silent_no_op(): + """Mutating a deprecated field after construction does not propagate to renderer_cfg.""" + cfg = CameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + ) + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + cfg.colorize_semantic_segmentation = False + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): + """TiledCameraCfg skips CameraCfg's per-field forwarder by design.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cfg = TiledCameraCfg( + height=64, + width=64, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=["rgb"], + colorize_semantic_segmentation=False, + ) + + tiled_warnings = [ + w for w in caught if issubclass(w.category, DeprecationWarning) and "TiledCameraCfg" in str(w.message) + ] + assert tiled_warnings + + field_warnings = [ + w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg.colorize_" in str(w.message) + ] + assert field_warnings == [] + + assert cfg.renderer_cfg.colorize_semantic_segmentation is True + + +# ----------------------------------------------------------------------------- +# Renderer.supported_output_types contract +# ----------------------------------------------------------------------------- + + +def _make_isaac_rtx_renderer(cfg: IsaacRtxRendererCfg | None = None): + """Construct an ``IsaacRtxRenderer`` instance without invoking its sim-coupled ``__init__``.""" + pytest.importorskip("pxr") + pytest.importorskip("isaacsim.core") + from isaaclab_physx.renderers.isaac_rtx_renderer import IsaacRtxRenderer + + renderer = IsaacRtxRenderer.__new__(IsaacRtxRenderer) + renderer.cfg = cfg if cfg is not None else IsaacRtxRendererCfg() + return renderer + + +def _fake_sim_version(major: int): + """Return a stand-in for ``get_isaac_sim_version()`` exposing only ``.major``.""" + + class _V: + pass + + v = _V() + v.major = major + return v + + +def test_isaac_rtx_supported_output_types_sim6_includes_albedo_and_simple_shading(): + renderer = _make_isaac_rtx_renderer() + + with patch( + "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", + return_value=_fake_sim_version(6), + ): + specs = renderer.supported_output_types() + + assert CameraDataType.ALBEDO in specs + for shading in ( + CameraDataType.SIMPLE_SHADING_CONSTANT_DIFFUSE, + CameraDataType.SIMPLE_SHADING_DIFFUSE_MDL, + CameraDataType.SIMPLE_SHADING_FULL_MDL, + ): + assert shading in specs + assert specs[shading] == OutputSpec(3, torch.uint8) + assert specs[CameraDataType.ALBEDO] == OutputSpec(4, torch.uint8) + + +def test_isaac_rtx_supported_output_types_pre_sim6_omits_albedo_and_simple_shading(): + renderer = _make_isaac_rtx_renderer() + + with patch( + "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", + return_value=_fake_sim_version(5), + ): + specs = renderer.supported_output_types() + + assert CameraDataType.ALBEDO not in specs + for shading in ( + CameraDataType.SIMPLE_SHADING_CONSTANT_DIFFUSE, + CameraDataType.SIMPLE_SHADING_DIFFUSE_MDL, + CameraDataType.SIMPLE_SHADING_FULL_MDL, + ): + assert shading not in specs + # Color/depth/etc. still ship pre-sim 6. + assert specs[CameraDataType.RGBA] == OutputSpec(4, torch.uint8) + assert specs[CameraDataType.DEPTH] == OutputSpec(1, torch.float32) + + +@pytest.mark.parametrize( + "data_type,flag_attr", + [ + (CameraDataType.SEMANTIC_SEGMENTATION, "colorize_semantic_segmentation"), + (CameraDataType.INSTANCE_SEGMENTATION_FAST, "colorize_instance_segmentation"), + (CameraDataType.INSTANCE_ID_SEGMENTATION_FAST, "colorize_instance_id_segmentation"), + ], +) +def test_isaac_rtx_segmentation_specs_follow_colorize_flags(data_type, flag_attr): + """Each segmentation entry's spec follows the corresponding ``colorize_*`` flag.""" + cfg_colorized = IsaacRtxRendererCfg() + setattr(cfg_colorized, flag_attr, True) + cfg_raw = IsaacRtxRendererCfg() + setattr(cfg_raw, flag_attr, False) + + with patch( + "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", + return_value=_fake_sim_version(6), + ): + specs_colorized = _make_isaac_rtx_renderer(cfg_colorized).supported_output_types() + specs_raw = _make_isaac_rtx_renderer(cfg_raw).supported_output_types() + + assert specs_colorized[data_type] == OutputSpec(4, torch.uint8) + assert specs_raw[data_type] == OutputSpec(1, torch.int32) + + +def test_newton_warp_supported_output_types_key_set(): + pytest.importorskip("isaaclab_newton") + pytest.importorskip("newton") + from isaaclab_newton.renderers.newton_warp_renderer import NewtonWarpRenderer + from isaaclab_newton.renderers.newton_warp_renderer_cfg import NewtonWarpRendererCfg + + renderer = NewtonWarpRenderer.__new__(NewtonWarpRenderer) + renderer.cfg = NewtonWarpRendererCfg() + specs = renderer.supported_output_types() + + assert set(specs.keys()) == { + CameraDataType.RGB, + CameraDataType.RGBA, + CameraDataType.ALBEDO, + CameraDataType.DEPTH, + CameraDataType.NORMALS, + CameraDataType.INSTANCE_SEGMENTATION_FAST, + } + + +def test_ovrtx_supported_output_types_key_set(): + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + from isaaclab_ov.renderers import OVRTXRendererCfg + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + specs = renderer.supported_output_types() + + assert set(specs.keys()) == { + CameraDataType.RGB, + CameraDataType.RGBA, + CameraDataType.ALBEDO, + CameraDataType.SEMANTIC_SEGMENTATION, + CameraDataType.DEPTH, + CameraDataType.DISTANCE_TO_IMAGE_PLANE, + CameraDataType.DISTANCE_TO_CAMERA, + } + + +# ----------------------------------------------------------------------------- +# CameraData allocation +# ----------------------------------------------------------------------------- + + +def _make_camera_cfg(data_types: list[str]) -> CameraCfg: + return CameraCfg( + height=8, + width=16, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=data_types, + ) + + +def test_camera_data_allocates_supported_subset_and_aliases_rgb(): + """``CameraData`` allocates the intersection of requested + supported and aliases rgb into rgba.""" + cfg = _make_camera_cfg(["rgb", "rgba", "depth"]) + specs = { + CameraDataType.RGBA: OutputSpec(4, torch.uint8), + CameraDataType.RGB: OutputSpec(3, torch.uint8), + CameraDataType.DEPTH: OutputSpec(1, torch.float32), + CameraDataType.NORMALS: OutputSpec(3, torch.float32), + } + data = CameraData.allocate( + data_types=cfg.data_types, height=8, width=16, num_views=2, device="cpu", supported_specs=specs + ) + + assert set(data.output.keys()) == {"rgba", "rgb", "depth"} + assert data.output["rgba"].shape == (2, 8, 16, 4) + assert data.output["rgba"].dtype == torch.uint8 + assert data.output["depth"].shape == (2, 8, 16, 1) + assert data.output["depth"].dtype == torch.float32 + assert data.output["rgb"].data_ptr() == data.output["rgba"].data_ptr() + assert data.image_shape == (8, 16) + assert data.info == {"rgba": None, "rgb": None, "depth": None} + + +def test_camera_data_drops_requested_types_not_in_supported_specs(): + """Requested types absent from ``supported_specs`` are absent from ``data.output``.""" + cfg = _make_camera_cfg(["rgb", "normals"]) + specs = {CameraDataType.RGBA: OutputSpec(4, torch.uint8), CameraDataType.RGB: OutputSpec(3, torch.uint8)} + data = CameraData.allocate( + data_types=cfg.data_types, height=4, width=4, num_views=1, device="cpu", supported_specs=specs + ) + + assert "normals" not in data.output + assert {"rgb", "rgba"} <= set(data.output.keys()) + + +def test_camera_data_no_arg_construction_yields_empty_container(): + """Bare ``CameraData()`` continues to produce an all-``None`` container (back-compat).""" + data = CameraData() + assert data.pos_w is None + assert data.quat_w_world is None + assert data.intrinsic_matrices is None + assert data.output is None + assert data.info is None + assert data.image_shape is None + + +def test_camera_data_segmentation_dtype_follows_supported_spec(): + """``CameraData`` consumes the layout fact (dtype) without knowing about ``colorize_*`` flags.""" + cfg = _make_camera_cfg(["instance_segmentation_fast"]) + raw_specs = {CameraDataType.INSTANCE_SEGMENTATION_FAST: OutputSpec(1, torch.int32)} + colorized_specs = {CameraDataType.INSTANCE_SEGMENTATION_FAST: OutputSpec(4, torch.uint8)} + + raw = CameraData.allocate( + data_types=cfg.data_types, height=4, width=4, num_views=1, device="cpu", supported_specs=raw_specs + ) + colorized = CameraData.allocate( + data_types=cfg.data_types, height=4, width=4, num_views=1, device="cpu", supported_specs=colorized_specs + ) + + assert raw.output["instance_segmentation_fast"].dtype == torch.int32 + assert raw.output["instance_segmentation_fast"].shape == (1, 4, 4, 1) + assert colorized.output["instance_segmentation_fast"].dtype == torch.uint8 + assert colorized.output["instance_segmentation_fast"].shape == (1, 4, 4, 4) + + +# ----------------------------------------------------------------------------- +# OVRTX zero-copy consolidation +# ----------------------------------------------------------------------------- + + +def _make_ovrtx_render_data(): + """Construct a minimal OVRTXRenderData without invoking its sensor-based __init__.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderData + + rd = OVRTXRenderData.__new__(OVRTXRenderData) + rd.warp_buffers = {} + return rd + + +def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): + """OVRTXRenderer.set_outputs publishes warp views over the caller's torch storage.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + import warp as wp + from isaaclab_ov.renderers import OVRTXRendererCfg + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + + if not torch.cuda.is_available(): + pytest.skip("OVRTX zero-copy wrapping requires a CUDA device") + device = "cuda" + + cfg = _make_camera_cfg(["rgb", "rgba", "depth"]) + data = CameraData.allocate( + data_types=cfg.data_types, + height=8, + width=16, + num_views=2, + device=device, + supported_specs=renderer.supported_output_types(), + ) + render_data = _make_ovrtx_render_data() + renderer.set_outputs(render_data, data.output) + + assert set(render_data.warp_buffers.keys()) >= {"rgba", "depth"} + assert render_data.warp_buffers["rgba"].ptr == wp.from_torch(data.output["rgba"]).ptr + assert render_data.warp_buffers["depth"].ptr == wp.from_torch(data.output["depth"]).ptr + assert "rgb" not in render_data.warp_buffers + + +def test_ovrtx_read_output_is_a_no_op_after_consolidation(): + """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" + pytest.importorskip("isaaclab_ov") + pytest.importorskip("ovrtx") + from isaaclab_ov.renderers import OVRTXRendererCfg + from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + render_data = _make_ovrtx_render_data() + camera_data = CameraData() + camera_data.info = {} + camera_data.output = {} + + result = renderer.read_output(render_data, camera_data) + assert result is None + assert render_data.warp_buffers == {} + assert camera_data.info == {} + assert camera_data.output == {} diff --git a/source/isaaclab/test/renderers/test_create_output_buffers.py b/source/isaaclab/test/renderers/test_create_output_buffers.py deleted file mode 100644 index 7e7a375b38b6..000000000000 --- a/source/isaaclab/test/renderers/test_create_output_buffers.py +++ /dev/null @@ -1,209 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Tests for the renderer-owned output buffers contract and CameraCfg deprecation forwarding.""" - -import warnings - -import pytest -import torch - -pytest.importorskip("isaaclab_physx") - -from isaaclab_physx.renderers import IsaacRtxRendererCfg - -from isaaclab.sensors.camera import CameraCfg, TiledCameraCfg -from isaaclab.sim import PinholeCameraCfg - -_SPAWN = PinholeCameraCfg( - focal_length=24.0, - focus_distance=400.0, - horizontal_aperture=20.955, - clipping_range=(0.1, 1.0e5), -) - - -# ----------------------------------------------------------------------------- -# CameraCfg deprecation forwarding -# ----------------------------------------------------------------------------- - - -@pytest.mark.parametrize( - "field_name,deprecated_value", - [ - ("colorize_semantic_segmentation", False), - ("colorize_instance_segmentation", False), - ("colorize_instance_id_segmentation", False), - ("semantic_filter", ["class"]), - ("semantic_segmentation_mapping", {"class:cube": (1, 2, 3, 4)}), - ("depth_clipping_behavior", "max"), - ], -) -def test_camera_cfg_forwards_deprecated_fields_to_renderer_cfg(field_name, deprecated_value): - """Deprecated RTX-flavored field set on CameraCfg lands on renderer_cfg and warns.""" - kwargs = { - "height": 64, - "width": 64, - "prim_path": "/World/Camera", - "spawn": _SPAWN, - "data_types": ["rgb"], - field_name: deprecated_value, - } - with warnings.catch_warnings(record=True) as caught: - warnings.simplefilter("always") - cfg = CameraCfg(**kwargs) - - deprecation_warnings = [w for w in caught if issubclass(w.category, DeprecationWarning)] - assert any(f"CameraCfg.{field_name}" in str(w.message) for w in deprecation_warnings) - assert getattr(cfg.renderer_cfg, field_name) == deprecated_value - - -def test_camera_cfg_default_does_not_warn_or_forward(): - """Default-valued deprecated fields stay silent.""" - with warnings.catch_warnings(record=True) as caught: - warnings.simplefilter("always") - cfg = CameraCfg( - height=64, - width=64, - prim_path="/World/Camera", - spawn=_SPAWN, - data_types=["rgb"], - ) - - deprecation_warnings = [ - w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg." in str(w.message) - ] - assert deprecation_warnings == [] - assert cfg.renderer_cfg.colorize_semantic_segmentation is True - - -def test_camera_cfg_post_construction_mutation_is_silent_no_op(): - """Mutating a deprecated field after construction does not propagate to renderer_cfg.""" - cfg = CameraCfg( - height=64, - width=64, - prim_path="/World/Camera", - spawn=_SPAWN, - data_types=["rgb"], - ) - assert cfg.renderer_cfg.colorize_semantic_segmentation is True - cfg.colorize_semantic_segmentation = False - assert cfg.renderer_cfg.colorize_semantic_segmentation is True - - -def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): - """TiledCameraCfg skips CameraCfg's per-field forwarder by design.""" - with warnings.catch_warnings(record=True) as caught: - warnings.simplefilter("always") - cfg = TiledCameraCfg( - height=64, - width=64, - prim_path="/World/Camera", - spawn=_SPAWN, - data_types=["rgb"], - colorize_semantic_segmentation=False, - ) - - tiled_warnings = [ - w for w in caught if issubclass(w.category, DeprecationWarning) and "TiledCameraCfg" in str(w.message) - ] - assert tiled_warnings - - field_warnings = [ - w for w in caught if issubclass(w.category, DeprecationWarning) and "CameraCfg.colorize_" in str(w.message) - ] - assert field_warnings == [] - - assert cfg.renderer_cfg.colorize_semantic_segmentation is True - - -# ----------------------------------------------------------------------------- -# IsaacRtxRenderer.create_output_buffers contract -# ----------------------------------------------------------------------------- - - -def test_isaac_rtx_create_output_buffers_omits_unsupported_and_aliases_rgb(): - """RTX backend drops names it cannot produce; rgb aliases rgba storage.""" - pytest.importorskip("pxr") - pytest.importorskip("isaacsim.core") - from isaaclab_physx.renderers.isaac_rtx_renderer import IsaacRtxRenderer - - renderer = IsaacRtxRenderer.__new__(IsaacRtxRenderer) - renderer.cfg = IsaacRtxRendererCfg() - - requested = ["rgb", "rgba", "depth", "definitely_not_supported"] - buffers = renderer.create_output_buffers(data_types=requested, height=8, width=16, num_views=2, device="cpu") - - assert "definitely_not_supported" not in buffers - assert {"rgb", "rgba", "depth"} <= set(buffers.keys()) - assert buffers["rgba"].shape == (2, 8, 16, 4) - assert buffers["rgba"].dtype == torch.uint8 - assert buffers["depth"].shape == (2, 8, 16, 1) - assert buffers["depth"].dtype == torch.float32 - assert buffers["rgb"].data_ptr() == buffers["rgba"].data_ptr() - - -# ----------------------------------------------------------------------------- -# OVRTX zero-copy consolidation -# ----------------------------------------------------------------------------- - - -def _make_ovrtx_render_data(): - """Construct a minimal OVRTXRenderData without invoking its sensor-based __init__.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderData - - rd = OVRTXRenderData.__new__(OVRTXRenderData) - rd.warp_buffers = {} - return rd - - -def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): - """OVRTXRenderer.set_outputs publishes warp views over the caller's torch storage.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - import warp as wp - from isaaclab_ov.renderers import OVRTXRendererCfg - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer - - renderer = OVRTXRenderer(OVRTXRendererCfg()) - - if not torch.cuda.is_available(): - pytest.skip("OVRTX zero-copy wrapping requires a CUDA device") - device = "cuda" - - buffers = renderer.create_output_buffers( - data_types=["rgb", "rgba", "depth"], height=8, width=16, num_views=2, device=device - ) - render_data = _make_ovrtx_render_data() - renderer.set_outputs(render_data, buffers) - - assert set(render_data.warp_buffers.keys()) >= {"rgba", "depth"} - assert render_data.warp_buffers["rgba"].ptr == wp.from_torch(buffers["rgba"]).ptr - assert render_data.warp_buffers["depth"].ptr == wp.from_torch(buffers["depth"]).ptr - assert "rgb" not in render_data.warp_buffers - - -def test_ovrtx_read_output_is_a_no_op_after_consolidation(): - """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - from isaaclab_ov.renderers import OVRTXRendererCfg - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer - - from isaaclab.sensors.camera.camera_data import CameraData - - renderer = OVRTXRenderer(OVRTXRendererCfg()) - render_data = _make_ovrtx_render_data() - camera_data = CameraData() - camera_data.info = {} - camera_data.output = {} - - result = renderer.read_output(render_data, camera_data) - assert result is None - assert render_data.warp_buffers == {} - assert camera_data.info == {} - assert camera_data.output == {} diff --git a/source/isaaclab/test/renderers/test_renderer_factory.py b/source/isaaclab/test/renderers/test_renderer_factory.py index e5ded56e6e34..51dc7f0a075a 100644 --- a/source/isaaclab/test/renderers/test_renderer_factory.py +++ b/source/isaaclab/test/renderers/test_renderer_factory.py @@ -28,7 +28,7 @@ class MockRenderer(BaseRenderer): def __init__(self, cfg=None): pass - def create_output_buffers(self, data_types, height, width, num_views, device): + def supported_output_types(self): return {} def prepare_stage(self, stage, num_envs): diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index c912c72a44fb..632789410e1d 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -1091,17 +1091,16 @@ def test_camera_warns_once_on_unsupported_data_types(setup_sim_camera, caplog): camera_cfg = copy.deepcopy(camera_cfg) camera_cfg.data_types = ["rgba", "depth", "normals"] + from isaaclab.sensors.camera.camera_data import CameraDataType, OutputSpec + class _PartialRenderer(BaseRenderer): - """Returns only ``rgba`` regardless of what was asked for.""" + """Publishes only ``rgba`` in its supported-output contract.""" def __init__(self, cfg=None): self.cfg = cfg - def create_output_buffers(self, data_types, height, width, num_views, device): - buffers: dict[str, torch.Tensor] = {} - if "rgba" in data_types or "rgb" in data_types: - buffers["rgba"] = torch.zeros((num_views, height, width, 4), dtype=torch.uint8, device=device) - return buffers + def supported_output_types(self): + return {CameraDataType.RGBA: OutputSpec(4, torch.uint8)} def prepare_stage(self, stage, num_envs): pass diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index 71fa5861c005..27f65ea79e05 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -16,7 +16,7 @@ import torch import warp as wp -from isaaclab.renderers import BaseRenderer +from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec from isaaclab.sim import SimulationContext from isaaclab.utils.math import convert_camera_frame_orientation_convention @@ -31,13 +31,8 @@ class RenderData: - class OutputNames: - RGB = "rgb" - RGBA = "rgba" - ALBEDO = "albedo" - DEPTH = "depth" - NORMALS = "normals" - INSTANCE_SEGMENTATION = "instance_segmentation_fast" + # Back-compat alias for callers of ``RenderData.OutputNames``. + OutputNames = CameraDataType @dataclass class CameraOutputs: @@ -65,31 +60,31 @@ def __init__(self, newton_sensor: newton.sensors.SensorTiledCamera, sensor: Sens def set_outputs(self, output_data: dict[str, torch.Tensor]): for output_name, tensor_data in output_data.items(): - if output_name == RenderData.OutputNames.RGBA: + if output_name == CameraDataType.RGBA: self.outputs.color_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == RenderData.OutputNames.ALBEDO: + elif output_name == CameraDataType.ALBEDO: self.outputs.albedo_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == RenderData.OutputNames.DEPTH: + elif output_name == CameraDataType.DEPTH: self.outputs.depth_image = self._from_torch(tensor_data, dtype=wp.float32) - elif output_name == RenderData.OutputNames.NORMALS: + elif output_name == CameraDataType.NORMALS: self.outputs.normals_image = self._from_torch(tensor_data, dtype=wp.vec3f) - elif output_name == RenderData.OutputNames.INSTANCE_SEGMENTATION: + elif output_name == CameraDataType.INSTANCE_SEGMENTATION_FAST: self.outputs.instance_segmentation_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == RenderData.OutputNames.RGB: + elif output_name == CameraDataType.RGB: pass else: logger.warning(f"NewtonWarpRenderer - output type {output_name} is not yet supported") def get_output(self, output_name: str) -> wp.array: - if output_name == RenderData.OutputNames.RGBA: + if output_name == CameraDataType.RGBA: return self.outputs.color_image - elif output_name == RenderData.OutputNames.ALBEDO: + elif output_name == CameraDataType.ALBEDO: return self.outputs.albedo_image - elif output_name == RenderData.OutputNames.DEPTH: + elif output_name == CameraDataType.DEPTH: return self.outputs.depth_image - elif output_name == RenderData.OutputNames.NORMALS: + elif output_name == CameraDataType.NORMALS: return self.outputs.normals_image - elif output_name == RenderData.OutputNames.INSTANCE_SEGMENTATION: + elif output_name == CameraDataType.INSTANCE_SEGMENTATION_FAST: return self.outputs.instance_segmentation_image return None @@ -185,38 +180,18 @@ def __init__(self, cfg: NewtonWarpRendererCfg): if cfg.create_default_light: self.newton_sensor.utils.create_default_light(enable_shadows=cfg.enable_shadows) - def create_output_buffers( - self, - data_types: list[str], - height: int, - width: int, - num_views: int, - device: torch.device | str, - ) -> dict[str, torch.Tensor]: - """Allocate output tensors for the data types Newton Warp can produce. - See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" - buffers: dict[str, torch.Tensor] = {} - requested = set(data_types) - names = RenderData.OutputNames - - def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: - return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() - - if names.RGBA in requested or names.RGB in requested: - buffers[names.RGBA] = _zeros(4, torch.uint8) - buffers[names.RGB] = buffers[names.RGBA][..., :3] - if names.ALBEDO in requested: - buffers[names.ALBEDO] = _zeros(4, torch.uint8) - if names.DEPTH in requested: - buffers[names.DEPTH] = _zeros(1, torch.float32) - if names.NORMALS in requested: - buffers[names.NORMALS] = _zeros(3, torch.float32) - if names.INSTANCE_SEGMENTATION in requested: - if self.cfg.colorize_instance_segmentation: - buffers[names.INSTANCE_SEGMENTATION] = _zeros(4, torch.uint8) - else: - buffers[names.INSTANCE_SEGMENTATION] = _zeros(1, torch.int32) - return buffers + def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + """Publish the per-output layout this Newton Warp backend writes. + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.supported_output_types`.""" + seg_spec = OutputSpec(4, torch.uint8) if self.cfg.colorize_instance_segmentation else OutputSpec(1, torch.int32) + return { + CameraDataType.RGBA: OutputSpec(4, torch.uint8), + CameraDataType.RGB: OutputSpec(3, torch.uint8), + CameraDataType.ALBEDO: OutputSpec(4, torch.uint8), + CameraDataType.DEPTH: OutputSpec(1, torch.float32), + CameraDataType.NORMALS: OutputSpec(3, torch.float32), + CameraDataType.INSTANCE_SEGMENTATION_FAST: seg_spec, + } def prepare_stage(self, stage: Any, num_envs: int) -> None: """No-op for Newton Warp - uses Newton scene directly without stage export. diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 5014c1cbff8e..3c7f4bd8e1d5 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -39,7 +39,7 @@ from ovrtx import Device, PrimMode, Renderer, RendererConfig, Semantic -from isaaclab.renderers.base_renderer import BaseRenderer +from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec from isaaclab.utils.math import convert_camera_frame_orientation_convention from .ovrtx_renderer_cfg import OVRTXRendererCfg @@ -90,33 +90,18 @@ class OVRTXRenderer(BaseRenderer): cfg: OVRTXRendererCfg - def create_output_buffers( - self, - data_types: list[str], - height: int, - width: int, - num_views: int, - device: torch.device | str, - ) -> dict[str, torch.Tensor]: - """Allocate output tensors for the data types OVRTX can produce. - See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" - buffers: dict[str, torch.Tensor] = {} - requested = set(data_types) - - def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: - return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() - - if "rgba" in requested or "rgb" in requested: - buffers["rgba"] = _zeros(4, torch.uint8) - buffers["rgb"] = buffers["rgba"][..., :3] - if "albedo" in requested: - buffers["albedo"] = _zeros(4, torch.uint8) - if "semantic_segmentation" in requested: - buffers["semantic_segmentation"] = _zeros(4, torch.uint8) - for depth_key in ("depth", "distance_to_image_plane", "distance_to_camera"): - if depth_key in requested: - buffers[depth_key] = _zeros(1, torch.float32) - return buffers + def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + """Publish the per-output layout this OVRTX backend writes. + See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.supported_output_types`.""" + return { + CameraDataType.RGBA: OutputSpec(4, torch.uint8), + CameraDataType.RGB: OutputSpec(3, torch.uint8), + CameraDataType.ALBEDO: OutputSpec(4, torch.uint8), + CameraDataType.SEMANTIC_SEGMENTATION: OutputSpec(4, torch.uint8), + CameraDataType.DEPTH: OutputSpec(1, torch.float32), + CameraDataType.DISTANCE_TO_IMAGE_PLANE: OutputSpec(1, torch.float32), + CameraDataType.DISTANCE_TO_CAMERA: OutputSpec(1, torch.float32), + } def __init__(self, cfg: OVRTXRendererCfg): self.cfg = cfg diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py index e198cede3eb8..ac035cd4806d 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py @@ -22,7 +22,7 @@ from pxr import Sdf from isaaclab.app.settings_manager import get_settings_manager -from isaaclab.renderers import BaseRenderer +from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec from isaaclab.utils.version import get_isaac_sim_version from isaaclab.utils.warp.kernels import reshape_tiled_image @@ -83,56 +83,42 @@ def __init__(self, cfg: IsaacRtxRendererCfg): ) # ``/isaaclab/render/rtx_sensors`` is owned by ``Camera.__init__`` (must be set pre-``sim.reset()``). - def create_output_buffers( - self, - data_types: list[str], - height: int, - width: int, - num_views: int, - device: torch.device | str, - ) -> dict[str, torch.Tensor]: - """Allocate Replicator-shaped output tensors for the data types Isaac RTX can produce. - See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_output_buffers`.""" - sim_major = get_isaac_sim_version().major + def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + """Publish the per-output Replicator layout this RTX backend writes. - buffers: dict[str, torch.Tensor] = {} - requested = set(data_types) + ``ALBEDO`` and the three ``SIMPLE_SHADING_*`` outputs require Isaac Sim 6.0+ + and are omitted on older versions. The three segmentation outputs report + ``OutputSpec(4, uint8)`` when the matching ``self.cfg.colorize_*`` flag is + set, otherwise ``OutputSpec(1, int32)``. + """ + sim_major = get_isaac_sim_version().major - def _zeros(channels: int, dtype: torch.dtype) -> torch.Tensor: - return torch.zeros((num_views, height, width, channels), dtype=dtype, device=device).contiguous() + specs: dict[CameraDataType, OutputSpec] = { + # Replicator's native layout for color output is rgba/uint8; + # ``Camera`` aliases ``rgb`` as a view into ``rgba`` storage. + CameraDataType.RGBA: OutputSpec(4, torch.uint8), + CameraDataType.RGB: OutputSpec(3, torch.uint8), + CameraDataType.DEPTH: OutputSpec(1, torch.float32), + CameraDataType.DISTANCE_TO_IMAGE_PLANE: OutputSpec(1, torch.float32), + CameraDataType.DISTANCE_TO_CAMERA: OutputSpec(1, torch.float32), + CameraDataType.NORMALS: OutputSpec(3, torch.float32), + CameraDataType.MOTION_VECTORS: OutputSpec(2, torch.float32), + } - if "rgba" in requested or "rgb" in requested: - buffers["rgba"] = _zeros(4, torch.uint8) - # rgb shares storage with rgba (Replicator's native layout). - buffers["rgb"] = buffers["rgba"][..., :3] - if "albedo" in requested and sim_major >= 6: - buffers["albedo"] = _zeros(4, torch.uint8) if sim_major >= 6: + specs[CameraDataType.ALBEDO] = OutputSpec(4, torch.uint8) for shading_type in SIMPLE_SHADING_MODES: - if shading_type in requested: - buffers[shading_type] = _zeros(3, torch.uint8) - for depth_key in ("depth", "distance_to_image_plane", "distance_to_camera"): - if depth_key in requested: - buffers[depth_key] = _zeros(1, torch.float32) - if "normals" in requested: - buffers["normals"] = _zeros(3, torch.float32) - if "motion_vectors" in requested: - buffers["motion_vectors"] = _zeros(2, torch.float32) + specs[CameraDataType(shading_type)] = OutputSpec(3, torch.uint8) seg_specs = ( - ("semantic_segmentation", self.cfg.colorize_semantic_segmentation), - ("instance_segmentation_fast", self.cfg.colorize_instance_segmentation), - ("instance_id_segmentation_fast", self.cfg.colorize_instance_id_segmentation), + (CameraDataType.SEMANTIC_SEGMENTATION, self.cfg.colorize_semantic_segmentation), + (CameraDataType.INSTANCE_SEGMENTATION_FAST, self.cfg.colorize_instance_segmentation), + (CameraDataType.INSTANCE_ID_SEGMENTATION_FAST, self.cfg.colorize_instance_id_segmentation), ) for name, colorize in seg_specs: - if name not in requested: - continue - if colorize: - buffers[name] = _zeros(4, torch.uint8) - else: - buffers[name] = _zeros(1, torch.int32) + specs[name] = OutputSpec(4, torch.uint8) if colorize else OutputSpec(1, torch.int32) - return buffers + return specs def prepare_stage(self, stage: Any, num_envs: int) -> None: """No-op for Isaac RTX - uses USD scene directly without export. From 05e5f08726a323a2e61752cf807506ba926fd891 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 23 Apr 2026 18:22:10 -0700 Subject: [PATCH 6/7] Formatting --- source/isaaclab/isaaclab/sensors/camera/camera_data.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_data.py b/source/isaaclab/isaaclab/sensors/camera/camera_data.py index 40f78660ff61..cc2106010952 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_data.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_data.py @@ -113,9 +113,7 @@ def allocate( except ValueError: unknown.append(name) if unknown: - raise ValueError( - f"Unknown CameraDataType name(s): {unknown}. Expected members of CameraDataType." - ) + raise ValueError(f"Unknown CameraDataType name(s): {unknown}. Expected members of CameraDataType.") # rgb is exposed as a view into rgba when the renderer publishes both, # so requesting either one allocates the shared rgba buffer. rgb_alias = ( From 0ee4df692719bff88b052516141f806fa493ee8f Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Mon, 27 Apr 2026 17:06:07 -0700 Subject: [PATCH 7/7] Rename contract --- source/isaaclab/docs/CHANGELOG.rst | 12 +- .../isaaclab/isaaclab/renderers/__init__.pyi | 6 +- .../isaaclab/renderers/base_renderer.py | 6 +- .../isaaclab/renderers/output_contract.py | 10 +- source/isaaclab/isaaclab/sensors/__init__.pyi | 8 +- .../isaaclab/sensors/camera/__init__.pyi | 6 +- .../isaaclab/sensors/camera/camera.py | 16 +- .../isaaclab/sensors/camera/camera_data.py | 36 +-- .../renderers/test_camera_output_contract.py | 261 +++--------------- source/isaaclab/test/sensors/test_camera.py | 4 +- .../renderers/newton_warp_renderer.py | 47 ++-- .../isaaclab_ov/renderers/ovrtx_renderer.py | 18 +- .../test/test_ovrtx_renderer_contract.py | 105 +++++++ .../renderers/isaac_rtx_renderer.py | 36 +-- .../renderers/isaac_rtx_renderer_cfg.py | 4 +- 15 files changed, 251 insertions(+), 324 deletions(-) create mode 100644 source/isaaclab_ov/test/test_ovrtx_renderer_contract.py diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 348661389088..0731a7b2d3d5 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -7,11 +7,13 @@ Changelog Changed ^^^^^^^ -* Renderer backends now own output-buffer allocation via a new - ``BaseRenderer.create_output_buffers`` hook. Backends are the source of truth - for shape, dtype, and any aliasing (e.g. ``rgb`` as a view into ``rgba``). - Requested data types the backend cannot produce are dropped with a single - warning, instead of being silently discarded later. +* :class:`~isaaclab.renderers.BaseRenderer` now publishes a renderer-owned + output contract via ``supported_output_types() -> {RenderBufferKind: RenderBufferSpec}``. + :class:`~isaaclab.sensors.camera.CameraData` allocates buffers for the + intersection of the requested ``data_types`` and the contract; ``rgb`` is + exposed as a view into ``rgba`` when both are published. Requested types + the active backend cannot produce are dropped with a single warning instead + of being silently discarded later. * :class:`~isaaclab_ov.renderers.OVRTXRenderer` now writes rendered tiles directly into the torch storage backing ``camera.data.output``, eliminating the per-frame ``wp.copy`` bridge. diff --git a/source/isaaclab/isaaclab/renderers/__init__.pyi b/source/isaaclab/isaaclab/renderers/__init__.pyi index 34d592036526..838cdb6e6bef 100644 --- a/source/isaaclab/isaaclab/renderers/__init__.pyi +++ b/source/isaaclab/isaaclab/renderers/__init__.pyi @@ -5,13 +5,13 @@ __all__ = [ "BaseRenderer", - "CameraDataType", - "OutputSpec", + "RenderBufferKind", + "RenderBufferSpec", "Renderer", "RendererCfg", ] from .base_renderer import BaseRenderer -from .output_contract import CameraDataType, OutputSpec +from .output_contract import RenderBufferKind, RenderBufferSpec from .renderer import Renderer from .renderer_cfg import RendererCfg diff --git a/source/isaaclab/isaaclab/renderers/base_renderer.py b/source/isaaclab/isaaclab/renderers/base_renderer.py index 5706c7d3ee8d..a8cba01ca6c6 100644 --- a/source/isaaclab/isaaclab/renderers/base_renderer.py +++ b/source/isaaclab/isaaclab/renderers/base_renderer.py @@ -10,7 +10,7 @@ from abc import ABC, abstractmethod from typing import TYPE_CHECKING, Any -from .output_contract import CameraDataType, OutputSpec +from .output_contract import RenderBufferKind, RenderBufferSpec if TYPE_CHECKING: import torch @@ -23,13 +23,13 @@ class BaseRenderer(ABC): """Abstract base class for renderer implementations.""" @abstractmethod - def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Per-output layout (channels + dtype) this renderer can produce. Outputs absent from the mapping are not produced by this backend. Returns: - Mapping from supported :class:`CameraDataType` to its :class:`OutputSpec`. + Mapping from supported :class:`RenderBufferKind` to its :class:`RenderBufferSpec`. """ pass diff --git a/source/isaaclab/isaaclab/renderers/output_contract.py b/source/isaaclab/isaaclab/renderers/output_contract.py index 713fcf1c78e7..bfa3fff41d8b 100644 --- a/source/isaaclab/isaaclab/renderers/output_contract.py +++ b/source/isaaclab/isaaclab/renderers/output_contract.py @@ -20,8 +20,8 @@ import torch -class CameraDataType(StrEnum): - """Canonical names for the per-pixel data types a renderer can publish. +class RenderBufferKind(StrEnum): + """Canonical names for the per-pixel render buffer kinds a renderer can publish. String values match the vocabulary used by :attr:`isaaclab.sensors.camera.CameraCfg.data_types`. @@ -44,11 +44,11 @@ class CameraDataType(StrEnum): @dataclass(frozen=True) -class OutputSpec: - """Per-pixel layout (channels + dtype) for one renderer output type.""" +class RenderBufferSpec: + """Per-pixel layout (channels + dtype) for one render buffer kind.""" channels: int """Number of per-pixel channels (last dimension of the allocated tensor).""" dtype: torch.dtype - """Torch dtype the renderer writes for this output type.""" + """Torch dtype the renderer writes for this render buffer kind.""" diff --git a/source/isaaclab/isaaclab/sensors/__init__.pyi b/source/isaaclab/isaaclab/sensors/__init__.pyi index 36471f3bf2ee..2a9d735f70ea 100644 --- a/source/isaaclab/isaaclab/sensors/__init__.pyi +++ b/source/isaaclab/isaaclab/sensors/__init__.pyi @@ -9,8 +9,8 @@ __all__ = [ "Camera", "CameraCfg", "CameraData", - "CameraDataType", - "OutputSpec", + "RenderBufferKind", + "RenderBufferSpec", "TiledCamera", "TiledCameraCfg", "transform_points", @@ -58,8 +58,8 @@ from .camera import ( Camera, CameraCfg, CameraData, - CameraDataType, - OutputSpec, + RenderBufferKind, + RenderBufferSpec, TiledCamera, TiledCameraCfg, transform_points, diff --git a/source/isaaclab/isaaclab/sensors/camera/__init__.pyi b/source/isaaclab/isaaclab/sensors/camera/__init__.pyi index 3b5873d19bc8..cac009dea0d4 100644 --- a/source/isaaclab/isaaclab/sensors/camera/__init__.pyi +++ b/source/isaaclab/isaaclab/sensors/camera/__init__.pyi @@ -7,8 +7,8 @@ __all__ = [ "Camera", "CameraCfg", "CameraData", - "CameraDataType", - "OutputSpec", + "RenderBufferKind", + "RenderBufferSpec", "TiledCamera", "TiledCameraCfg", "transform_points", @@ -19,7 +19,7 @@ __all__ = [ from .camera import Camera from .camera_cfg import CameraCfg -from .camera_data import CameraData, CameraDataType, OutputSpec +from .camera_data import CameraData, RenderBufferKind, RenderBufferSpec from .tiled_camera import TiledCamera from .tiled_camera_cfg import TiledCameraCfg from .utils import ( diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 4c0bb7bbfe51..2244d191db72 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -27,7 +27,7 @@ ) from ..sensor_base import SensorBase -from .camera_data import CameraData, CameraDataType +from .camera_data import CameraData, RenderBufferKind if TYPE_CHECKING: from .camera_cfg import CameraCfg @@ -107,13 +107,11 @@ def __init__(self, cfg: CameraCfg): # initialize base class super().__init__(cfg) - # TODO: Camera should not branch on a specific renderer_type string. Replace with a - # generic opt-in flag on RendererCfg (e.g. ``requires_kit_rtx_sensors_flag``) that - # RTX-family cfgs set to True, so this branch carries no renderer-specific knowledge. - # The flag must flip at scene-construction time (before sim.reset()) because - # SimulationContext.is_rendering and several env classes branch on it pre-reset; - # flipping inside the renderer's __init__ (which only runs at sim.reset()) would - # silently break that timing. + # TODO(follow-up PR): move this flag flip out of Camera. The cleanest path is + # an apply_pre_reset_settings() hook on RendererCfg (default no-op) that + # IsaacRtxRendererCfg overrides to flip /isaaclab/render/rtx_sensors. The + # flag must be set pre-sim.reset() because SimulationContext.is_rendering + # and several env classes read it before the renderer's __init__ runs. if self.cfg.renderer_cfg.renderer_type == "isaac_rtx": get_settings_manager().set_bool("/isaaclab/render/rtx_sensors", True) @@ -454,7 +452,7 @@ def _create_buffers(self): unsupported: list[str] = [] for name in self.cfg.data_types: try: - if CameraDataType(name) in specs: + if RenderBufferKind(name) in specs: known.append(name) else: unsupported.append(name) diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_data.py b/source/isaaclab/isaaclab/sensors/camera/camera_data.py index cc2106010952..6ec5484531b2 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_data.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_data.py @@ -11,10 +11,10 @@ import torch # Re-exported as part of the public isaaclab.sensors.camera API -from isaaclab.renderers.output_contract import CameraDataType, OutputSpec +from isaaclab.renderers.output_contract import RenderBufferKind, RenderBufferSpec from isaaclab.utils.math import convert_camera_frame_orientation_convention -__all__ = ["CameraData", "CameraDataType", "OutputSpec"] +__all__ = ["CameraData", "RenderBufferKind", "RenderBufferSpec"] @dataclass @@ -78,23 +78,23 @@ def allocate( width: int, num_views: int, device: torch.device | str, - supported_specs: dict[CameraDataType, OutputSpec], + supported_specs: dict[RenderBufferKind, RenderBufferSpec], ) -> CameraData: """Build a :class:`CameraData` with output buffers pre-allocated. - Allocates one ``(num_views, height, width, channels)`` tensor per type + Allocates one ``(num_views, height, width, channels)`` tensor per kind in the intersection of ``data_types`` and ``supported_specs``, using - the channels and dtype from each :class:`OutputSpec`. + the channels and dtype from each :class:`RenderBufferSpec`. Args: data_types: Requested output names (typically :attr:`CameraCfg.data_types`). - Every name must be a member of :class:`CameraDataType`. + Every name must be a member of :class:`RenderBufferKind`. height: Image height in pixels. width: Image width in pixels. num_views: Number of camera views (batch dimension). device: Torch device on which to allocate the buffers. - supported_specs: Per-output layout the active renderer can produce, - keyed by :class:`CameraDataType`. Names absent from this mapping + supported_specs: Per-buffer layout the active renderer can produce, + keyed by :class:`RenderBufferKind`. Names absent from this mapping are not allocated. Returns: @@ -103,32 +103,32 @@ def allocate( Raises: ValueError: If ``data_types`` contains names that are not members of - :class:`CameraDataType`. + :class:`RenderBufferKind`. """ - requested: set[CameraDataType] = set() + requested: set[RenderBufferKind] = set() unknown: list[str] = [] for name in data_types: try: - requested.add(CameraDataType(name)) + requested.add(RenderBufferKind(name)) except ValueError: unknown.append(name) if unknown: - raise ValueError(f"Unknown CameraDataType name(s): {unknown}. Expected members of CameraDataType.") + raise ValueError(f"Unknown RenderBufferKind name(s): {unknown}. Expected members of RenderBufferKind.") # rgb is exposed as a view into rgba when the renderer publishes both, # so requesting either one allocates the shared rgba buffer. rgb_alias = ( - CameraDataType.RGBA in supported_specs - and CameraDataType.RGB in supported_specs - and (CameraDataType.RGB in requested or CameraDataType.RGBA in requested) + RenderBufferKind.RGBA in supported_specs + and RenderBufferKind.RGB in supported_specs + and (RenderBufferKind.RGB in requested or RenderBufferKind.RGBA in requested) ) if rgb_alias: - requested.update({CameraDataType.RGB, CameraDataType.RGBA}) + requested.update({RenderBufferKind.RGB, RenderBufferKind.RGBA}) buffers: dict[str, torch.Tensor] = {} for name, spec in supported_specs.items(): if name not in requested: continue - if rgb_alias and name == CameraDataType.RGB: + if rgb_alias and name == RenderBufferKind.RGB: continue buffers[str(name)] = torch.zeros( (num_views, height, width, spec.channels), @@ -136,7 +136,7 @@ def allocate( device=device, ).contiguous() if rgb_alias: - buffers[str(CameraDataType.RGB)] = buffers[str(CameraDataType.RGBA)][..., :3] + buffers[str(RenderBufferKind.RGB)] = buffers[str(RenderBufferKind.RGBA)][..., :3] return cls( image_shape=(height, width), diff --git a/source/isaaclab/test/renderers/test_camera_output_contract.py b/source/isaaclab/test/renderers/test_camera_output_contract.py index 2254d8ae55cb..2d6087d29708 100644 --- a/source/isaaclab/test/renderers/test_camera_output_contract.py +++ b/source/isaaclab/test/renderers/test_camera_output_contract.py @@ -3,28 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Tests for the renderer→camera output contract. - -The renderer publishes the per-output layout via -:meth:`isaaclab.renderers.BaseRenderer.supported_output_types`; ``CameraData`` -allocates storage for the supported subset of the requested types and aliases -``rgb`` into ``rgba``. These tests cover both halves of that contract plus -:class:`CameraCfg` deprecation forwarding (which feeds the renderer cfg the -contract is published from). -""" +"""Tests for the renderer→camera output contract.""" import warnings -from unittest.mock import patch import pytest import torch pytest.importorskip("isaaclab_physx") -from isaaclab_physx.renderers import IsaacRtxRendererCfg - from isaaclab.sensors.camera import CameraCfg, TiledCameraCfg -from isaaclab.sensors.camera.camera_data import CameraData, CameraDataType, OutputSpec +from isaaclab.sensors.camera.camera_data import CameraData, RenderBufferKind, RenderBufferSpec from isaaclab.sim import PinholeCameraCfg _SPAWN = PinholeCameraCfg( @@ -35,11 +24,6 @@ ) -# ----------------------------------------------------------------------------- -# CameraCfg deprecation forwarding -# ----------------------------------------------------------------------------- - - @pytest.mark.parametrize( "field_name,deprecated_value", [ @@ -52,7 +36,7 @@ ], ) def test_camera_cfg_forwards_deprecated_fields_to_renderer_cfg(field_name, deprecated_value): - """Deprecated RTX-flavored field set on CameraCfg lands on renderer_cfg and warns.""" + """Deprecated CameraCfg field is forwarded to renderer_cfg with a warning.""" kwargs = { "height": 64, "width": 64, @@ -104,7 +88,7 @@ def test_camera_cfg_post_construction_mutation_is_silent_no_op(): def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): - """TiledCameraCfg skips CameraCfg's per-field forwarder by design.""" + """TiledCameraCfg skips CameraCfg's per-field forwarder.""" with warnings.catch_warnings(record=True) as caught: warnings.simplefilter("always") cfg = TiledCameraCfg( @@ -129,101 +113,8 @@ def test_tiled_camera_cfg_does_not_forward_deprecated_fields(): assert cfg.renderer_cfg.colorize_semantic_segmentation is True -# ----------------------------------------------------------------------------- -# Renderer.supported_output_types contract -# ----------------------------------------------------------------------------- - - -def _make_isaac_rtx_renderer(cfg: IsaacRtxRendererCfg | None = None): - """Construct an ``IsaacRtxRenderer`` instance without invoking its sim-coupled ``__init__``.""" - pytest.importorskip("pxr") - pytest.importorskip("isaacsim.core") - from isaaclab_physx.renderers.isaac_rtx_renderer import IsaacRtxRenderer - - renderer = IsaacRtxRenderer.__new__(IsaacRtxRenderer) - renderer.cfg = cfg if cfg is not None else IsaacRtxRendererCfg() - return renderer - - -def _fake_sim_version(major: int): - """Return a stand-in for ``get_isaac_sim_version()`` exposing only ``.major``.""" - - class _V: - pass - - v = _V() - v.major = major - return v - - -def test_isaac_rtx_supported_output_types_sim6_includes_albedo_and_simple_shading(): - renderer = _make_isaac_rtx_renderer() - - with patch( - "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", - return_value=_fake_sim_version(6), - ): - specs = renderer.supported_output_types() - - assert CameraDataType.ALBEDO in specs - for shading in ( - CameraDataType.SIMPLE_SHADING_CONSTANT_DIFFUSE, - CameraDataType.SIMPLE_SHADING_DIFFUSE_MDL, - CameraDataType.SIMPLE_SHADING_FULL_MDL, - ): - assert shading in specs - assert specs[shading] == OutputSpec(3, torch.uint8) - assert specs[CameraDataType.ALBEDO] == OutputSpec(4, torch.uint8) - - -def test_isaac_rtx_supported_output_types_pre_sim6_omits_albedo_and_simple_shading(): - renderer = _make_isaac_rtx_renderer() - - with patch( - "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", - return_value=_fake_sim_version(5), - ): - specs = renderer.supported_output_types() - - assert CameraDataType.ALBEDO not in specs - for shading in ( - CameraDataType.SIMPLE_SHADING_CONSTANT_DIFFUSE, - CameraDataType.SIMPLE_SHADING_DIFFUSE_MDL, - CameraDataType.SIMPLE_SHADING_FULL_MDL, - ): - assert shading not in specs - # Color/depth/etc. still ship pre-sim 6. - assert specs[CameraDataType.RGBA] == OutputSpec(4, torch.uint8) - assert specs[CameraDataType.DEPTH] == OutputSpec(1, torch.float32) - - -@pytest.mark.parametrize( - "data_type,flag_attr", - [ - (CameraDataType.SEMANTIC_SEGMENTATION, "colorize_semantic_segmentation"), - (CameraDataType.INSTANCE_SEGMENTATION_FAST, "colorize_instance_segmentation"), - (CameraDataType.INSTANCE_ID_SEGMENTATION_FAST, "colorize_instance_id_segmentation"), - ], -) -def test_isaac_rtx_segmentation_specs_follow_colorize_flags(data_type, flag_attr): - """Each segmentation entry's spec follows the corresponding ``colorize_*`` flag.""" - cfg_colorized = IsaacRtxRendererCfg() - setattr(cfg_colorized, flag_attr, True) - cfg_raw = IsaacRtxRendererCfg() - setattr(cfg_raw, flag_attr, False) - - with patch( - "isaaclab_physx.renderers.isaac_rtx_renderer.get_isaac_sim_version", - return_value=_fake_sim_version(6), - ): - specs_colorized = _make_isaac_rtx_renderer(cfg_colorized).supported_output_types() - specs_raw = _make_isaac_rtx_renderer(cfg_raw).supported_output_types() - - assert specs_colorized[data_type] == OutputSpec(4, torch.uint8) - assert specs_raw[data_type] == OutputSpec(1, torch.int32) - - def test_newton_warp_supported_output_types_key_set(): + """NewtonWarpRenderer publishes the documented key set.""" pytest.importorskip("isaaclab_newton") pytest.importorskip("newton") from isaaclab_newton.renderers.newton_warp_renderer import NewtonWarpRenderer @@ -234,40 +125,15 @@ def test_newton_warp_supported_output_types_key_set(): specs = renderer.supported_output_types() assert set(specs.keys()) == { - CameraDataType.RGB, - CameraDataType.RGBA, - CameraDataType.ALBEDO, - CameraDataType.DEPTH, - CameraDataType.NORMALS, - CameraDataType.INSTANCE_SEGMENTATION_FAST, - } - - -def test_ovrtx_supported_output_types_key_set(): - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - from isaaclab_ov.renderers import OVRTXRendererCfg - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer - - renderer = OVRTXRenderer(OVRTXRendererCfg()) - specs = renderer.supported_output_types() - - assert set(specs.keys()) == { - CameraDataType.RGB, - CameraDataType.RGBA, - CameraDataType.ALBEDO, - CameraDataType.SEMANTIC_SEGMENTATION, - CameraDataType.DEPTH, - CameraDataType.DISTANCE_TO_IMAGE_PLANE, - CameraDataType.DISTANCE_TO_CAMERA, + RenderBufferKind.RGB, + RenderBufferKind.RGBA, + RenderBufferKind.ALBEDO, + RenderBufferKind.DEPTH, + RenderBufferKind.NORMALS, + RenderBufferKind.INSTANCE_SEGMENTATION_FAST, } -# ----------------------------------------------------------------------------- -# CameraData allocation -# ----------------------------------------------------------------------------- - - def _make_camera_cfg(data_types: list[str]) -> CameraCfg: return CameraCfg( height=8, @@ -279,13 +145,13 @@ def _make_camera_cfg(data_types: list[str]) -> CameraCfg: def test_camera_data_allocates_supported_subset_and_aliases_rgb(): - """``CameraData`` allocates the intersection of requested + supported and aliases rgb into rgba.""" + """CameraData allocates the intersection of requested + supported and aliases rgb into rgba.""" cfg = _make_camera_cfg(["rgb", "rgba", "depth"]) specs = { - CameraDataType.RGBA: OutputSpec(4, torch.uint8), - CameraDataType.RGB: OutputSpec(3, torch.uint8), - CameraDataType.DEPTH: OutputSpec(1, torch.float32), - CameraDataType.NORMALS: OutputSpec(3, torch.float32), + RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.RGB: RenderBufferSpec(3, torch.uint8), + RenderBufferKind.DEPTH: RenderBufferSpec(1, torch.float32), + RenderBufferKind.NORMALS: RenderBufferSpec(3, torch.float32), } data = CameraData.allocate( data_types=cfg.data_types, height=8, width=16, num_views=2, device="cpu", supported_specs=specs @@ -302,9 +168,12 @@ def test_camera_data_allocates_supported_subset_and_aliases_rgb(): def test_camera_data_drops_requested_types_not_in_supported_specs(): - """Requested types absent from ``supported_specs`` are absent from ``data.output``.""" + """Requested types absent from supported_specs are absent from data.output.""" cfg = _make_camera_cfg(["rgb", "normals"]) - specs = {CameraDataType.RGBA: OutputSpec(4, torch.uint8), CameraDataType.RGB: OutputSpec(3, torch.uint8)} + specs = { + RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.RGB: RenderBufferSpec(3, torch.uint8), + } data = CameraData.allocate( data_types=cfg.data_types, height=4, width=4, num_views=1, device="cpu", supported_specs=specs ) @@ -314,7 +183,7 @@ def test_camera_data_drops_requested_types_not_in_supported_specs(): def test_camera_data_no_arg_construction_yields_empty_container(): - """Bare ``CameraData()`` continues to produce an all-``None`` container (back-compat).""" + """Bare CameraData() produces an all-None container.""" data = CameraData() assert data.pos_w is None assert data.quat_w_world is None @@ -325,10 +194,10 @@ def test_camera_data_no_arg_construction_yields_empty_container(): def test_camera_data_segmentation_dtype_follows_supported_spec(): - """``CameraData`` consumes the layout fact (dtype) without knowing about ``colorize_*`` flags.""" + """CameraData consumes the layout dtype declared by the renderer spec.""" cfg = _make_camera_cfg(["instance_segmentation_fast"]) - raw_specs = {CameraDataType.INSTANCE_SEGMENTATION_FAST: OutputSpec(1, torch.int32)} - colorized_specs = {CameraDataType.INSTANCE_SEGMENTATION_FAST: OutputSpec(4, torch.uint8)} + raw_specs = {RenderBufferKind.INSTANCE_SEGMENTATION_FAST: RenderBufferSpec(1, torch.int32)} + colorized_specs = {RenderBufferKind.INSTANCE_SEGMENTATION_FAST: RenderBufferSpec(4, torch.uint8)} raw = CameraData.allocate( data_types=cfg.data_types, height=4, width=4, num_views=1, device="cpu", supported_specs=raw_specs @@ -343,69 +212,17 @@ def test_camera_data_segmentation_dtype_follows_supported_spec(): assert colorized.output["instance_segmentation_fast"].shape == (1, 4, 4, 4) -# ----------------------------------------------------------------------------- -# OVRTX zero-copy consolidation -# ----------------------------------------------------------------------------- - - -def _make_ovrtx_render_data(): - """Construct a minimal OVRTXRenderData without invoking its sensor-based __init__.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderData - - rd = OVRTXRenderData.__new__(OVRTXRenderData) - rd.warp_buffers = {} - return rd - - -def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): - """OVRTXRenderer.set_outputs publishes warp views over the caller's torch storage.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - import warp as wp - from isaaclab_ov.renderers import OVRTXRendererCfg - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer - - renderer = OVRTXRenderer(OVRTXRendererCfg()) - - if not torch.cuda.is_available(): - pytest.skip("OVRTX zero-copy wrapping requires a CUDA device") - device = "cuda" - - cfg = _make_camera_cfg(["rgb", "rgba", "depth"]) - data = CameraData.allocate( - data_types=cfg.data_types, - height=8, - width=16, - num_views=2, - device=device, - supported_specs=renderer.supported_output_types(), - ) - render_data = _make_ovrtx_render_data() - renderer.set_outputs(render_data, data.output) - - assert set(render_data.warp_buffers.keys()) >= {"rgba", "depth"} - assert render_data.warp_buffers["rgba"].ptr == wp.from_torch(data.output["rgba"]).ptr - assert render_data.warp_buffers["depth"].ptr == wp.from_torch(data.output["depth"]).ptr - assert "rgb" not in render_data.warp_buffers - - -def test_ovrtx_read_output_is_a_no_op_after_consolidation(): - """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" - pytest.importorskip("isaaclab_ov") - pytest.importorskip("ovrtx") - from isaaclab_ov.renderers import OVRTXRendererCfg - from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderer - - renderer = OVRTXRenderer(OVRTXRendererCfg()) - render_data = _make_ovrtx_render_data() - camera_data = CameraData() - camera_data.info = {} - camera_data.output = {} - - result = renderer.read_output(render_data, camera_data) - assert result is None - assert render_data.warp_buffers == {} - assert camera_data.info == {} - assert camera_data.output == {} +def test_camera_data_allocate_raises_on_unknown_name(): + """An unknown data_types name raises ValueError naming the offender.""" + supported_specs = {RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8)} + with pytest.raises(ValueError) as exc_info: + CameraData.allocate( + data_types=["not_a_real_type"], + height=4, + width=4, + num_views=1, + device="cpu", + supported_specs=supported_specs, + ) + assert "not_a_real_type" in str(exc_info.value) + assert "RenderBufferKind" in str(exc_info.value) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index fd96dc9a9293..daed8e95773d 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -1087,7 +1087,7 @@ def test_camera_warns_once_on_unsupported_data_types(setup_sim_camera, caplog): camera_cfg = copy.deepcopy(camera_cfg) camera_cfg.data_types = ["rgba", "depth", "normals"] - from isaaclab.sensors.camera.camera_data import CameraDataType, OutputSpec + from isaaclab.sensors.camera.camera_data import RenderBufferKind, RenderBufferSpec class _PartialRenderer(BaseRenderer): """Publishes only ``rgba`` in its supported-output contract.""" @@ -1096,7 +1096,7 @@ def __init__(self, cfg=None): self.cfg = cfg def supported_output_types(self): - return {CameraDataType.RGBA: OutputSpec(4, torch.uint8)} + return {RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8)} def prepare_stage(self, stage, num_envs): pass diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index 7db10607e529..3fb198faf53d 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -16,7 +16,7 @@ import torch import warp as wp -from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec +from isaaclab.renderers import BaseRenderer, RenderBufferKind, RenderBufferSpec from isaaclab.sim import SimulationContext from isaaclab.utils.math import convert_camera_frame_orientation_convention @@ -32,7 +32,7 @@ class RenderData: # Back-compat alias for callers of ``RenderData.OutputNames``. - OutputNames = CameraDataType + OutputNames = RenderBufferKind @dataclass class CameraOutputs: @@ -60,31 +60,31 @@ def __init__(self, newton_sensor: newton.sensors.SensorTiledCamera, sensor: Sens def set_outputs(self, output_data: dict[str, torch.Tensor]): for output_name, tensor_data in output_data.items(): - if output_name == CameraDataType.RGBA: + if output_name == RenderBufferKind.RGBA: self.outputs.color_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == CameraDataType.ALBEDO: + elif output_name == RenderBufferKind.ALBEDO: self.outputs.albedo_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == CameraDataType.DEPTH: + elif output_name == RenderBufferKind.DEPTH: self.outputs.depth_image = self._from_torch(tensor_data, dtype=wp.float32) - elif output_name == CameraDataType.NORMALS: + elif output_name == RenderBufferKind.NORMALS: self.outputs.normals_image = self._from_torch(tensor_data, dtype=wp.vec3f) - elif output_name == CameraDataType.INSTANCE_SEGMENTATION_FAST: + elif output_name == RenderBufferKind.INSTANCE_SEGMENTATION_FAST: self.outputs.instance_segmentation_image = self._from_torch(tensor_data, dtype=wp.uint32) - elif output_name == CameraDataType.RGB: + elif output_name == RenderBufferKind.RGB: pass else: logger.warning(f"NewtonWarpRenderer - output type {output_name} is not yet supported") def get_output(self, output_name: str) -> wp.array: - if output_name == CameraDataType.RGBA: + if output_name == RenderBufferKind.RGBA: return self.outputs.color_image - elif output_name == CameraDataType.ALBEDO: + elif output_name == RenderBufferKind.ALBEDO: return self.outputs.albedo_image - elif output_name == CameraDataType.DEPTH: + elif output_name == RenderBufferKind.DEPTH: return self.outputs.depth_image - elif output_name == CameraDataType.NORMALS: + elif output_name == RenderBufferKind.NORMALS: return self.outputs.normals_image - elif output_name == CameraDataType.INSTANCE_SEGMENTATION_FAST: + elif output_name == RenderBufferKind.INSTANCE_SEGMENTATION_FAST: return self.outputs.instance_segmentation_image return None @@ -150,6 +150,7 @@ def __init__(self, cfg: NewtonWarpRendererCfg): requirement_for_renderer_type, ) + self.cfg = cfg sim = SimulationContext.instance() current_req = sim.get_scene_data_requirements() renderer_req = requirement_for_renderer_type("newton_warp") @@ -180,17 +181,21 @@ def __init__(self, cfg: NewtonWarpRendererCfg): if cfg.create_default_light: self.newton_sensor.utils.create_default_light(enable_shadows=cfg.enable_shadows) - def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Publish the per-output layout this Newton Warp backend writes. See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.supported_output_types`.""" - seg_spec = OutputSpec(4, torch.uint8) if self.cfg.colorize_instance_segmentation else OutputSpec(1, torch.int32) + seg_spec = ( + RenderBufferSpec(4, torch.uint8) + if self.cfg.colorize_instance_segmentation + else RenderBufferSpec(1, torch.int32) + ) return { - CameraDataType.RGBA: OutputSpec(4, torch.uint8), - CameraDataType.RGB: OutputSpec(3, torch.uint8), - CameraDataType.ALBEDO: OutputSpec(4, torch.uint8), - CameraDataType.DEPTH: OutputSpec(1, torch.float32), - CameraDataType.NORMALS: OutputSpec(3, torch.float32), - CameraDataType.INSTANCE_SEGMENTATION_FAST: seg_spec, + RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.RGB: RenderBufferSpec(3, torch.uint8), + RenderBufferKind.ALBEDO: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.DEPTH: RenderBufferSpec(1, torch.float32), + RenderBufferKind.NORMALS: RenderBufferSpec(3, torch.float32), + RenderBufferKind.INSTANCE_SEGMENTATION_FAST: seg_spec, } def prepare_stage(self, stage: Any, num_envs: int) -> None: diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 3c7f4bd8e1d5..5448a467eb3c 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -39,7 +39,7 @@ from ovrtx import Device, PrimMode, Renderer, RendererConfig, Semantic -from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec +from isaaclab.renderers import BaseRenderer, RenderBufferKind, RenderBufferSpec from isaaclab.utils.math import convert_camera_frame_orientation_convention from .ovrtx_renderer_cfg import OVRTXRendererCfg @@ -90,17 +90,17 @@ class OVRTXRenderer(BaseRenderer): cfg: OVRTXRendererCfg - def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Publish the per-output layout this OVRTX backend writes. See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.supported_output_types`.""" return { - CameraDataType.RGBA: OutputSpec(4, torch.uint8), - CameraDataType.RGB: OutputSpec(3, torch.uint8), - CameraDataType.ALBEDO: OutputSpec(4, torch.uint8), - CameraDataType.SEMANTIC_SEGMENTATION: OutputSpec(4, torch.uint8), - CameraDataType.DEPTH: OutputSpec(1, torch.float32), - CameraDataType.DISTANCE_TO_IMAGE_PLANE: OutputSpec(1, torch.float32), - CameraDataType.DISTANCE_TO_CAMERA: OutputSpec(1, torch.float32), + RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.RGB: RenderBufferSpec(3, torch.uint8), + RenderBufferKind.ALBEDO: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.SEMANTIC_SEGMENTATION: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.DEPTH: RenderBufferSpec(1, torch.float32), + RenderBufferKind.DISTANCE_TO_IMAGE_PLANE: RenderBufferSpec(1, torch.float32), + RenderBufferKind.DISTANCE_TO_CAMERA: RenderBufferSpec(1, torch.float32), } def __init__(self, cfg: OVRTXRendererCfg): diff --git a/source/isaaclab_ov/test/test_ovrtx_renderer_contract.py b/source/isaaclab_ov/test/test_ovrtx_renderer_contract.py new file mode 100644 index 000000000000..b6c590a54a54 --- /dev/null +++ b/source/isaaclab_ov/test/test_ovrtx_renderer_contract.py @@ -0,0 +1,105 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for the OVRTX renderer output contract.""" + +import pytest +import torch + +pytest.importorskip("isaaclab_ov") +pytest.importorskip("ovrtx") + +from isaaclab_ov.renderers import OVRTXRendererCfg +from isaaclab_ov.renderers.ovrtx_renderer import OVRTXRenderData, OVRTXRenderer + +from isaaclab.sensors.camera import CameraCfg +from isaaclab.sensors.camera.camera_data import CameraData, RenderBufferKind, RenderBufferSpec +from isaaclab.sim import PinholeCameraCfg + +pytestmark = pytest.mark.isaacsim_ci + +_SPAWN = PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), +) + + +def _make_camera_cfg(data_types: list[str]) -> CameraCfg: + return CameraCfg( + height=8, + width=16, + prim_path="/World/Camera", + spawn=_SPAWN, + data_types=data_types, + ) + + +def _make_ovrtx_render_data() -> OVRTXRenderData: + rd = OVRTXRenderData.__new__(OVRTXRenderData) + rd.warp_buffers = {} + return rd + + +def test_ovrtx_supported_output_types_key_set(): + """OVRTX publishes the documented key set and per-output spec.""" + renderer = OVRTXRenderer(OVRTXRendererCfg()) + specs = renderer.supported_output_types() + + assert set(specs.keys()) == { + RenderBufferKind.RGB, + RenderBufferKind.RGBA, + RenderBufferKind.ALBEDO, + RenderBufferKind.SEMANTIC_SEGMENTATION, + RenderBufferKind.DEPTH, + RenderBufferKind.DISTANCE_TO_IMAGE_PLANE, + RenderBufferKind.DISTANCE_TO_CAMERA, + } + assert specs[RenderBufferKind.RGBA] == RenderBufferSpec(4, torch.uint8) + assert specs[RenderBufferKind.DEPTH] == RenderBufferSpec(1, torch.float32) + + +def test_ovrtx_set_outputs_wraps_caller_torch_zero_copy(): + """OVRTXRenderer.set_outputs publishes warp views over the caller's torch storage.""" + import warp as wp + + renderer = OVRTXRenderer(OVRTXRendererCfg()) + + if not torch.cuda.is_available(): + pytest.skip("OVRTX zero-copy wrapping requires a CUDA device") + device = "cuda" + + cfg = _make_camera_cfg(["rgb", "rgba", "depth"]) + data = CameraData.allocate( + data_types=cfg.data_types, + height=8, + width=16, + num_views=2, + device=device, + supported_specs=renderer.supported_output_types(), + ) + render_data = _make_ovrtx_render_data() + renderer.set_outputs(render_data, data.output) + + assert set(render_data.warp_buffers.keys()) >= {"rgba", "depth"} + assert render_data.warp_buffers["rgba"].ptr == wp.from_torch(data.output["rgba"]).ptr + assert render_data.warp_buffers["depth"].ptr == wp.from_torch(data.output["depth"]).ptr + assert "rgb" not in render_data.warp_buffers + + +def test_ovrtx_read_output_is_a_no_op_after_consolidation(): + """OVRTXRenderer.read_output is a no-op once set_outputs wires up zero-copy.""" + renderer = OVRTXRenderer(OVRTXRendererCfg()) + render_data = _make_ovrtx_render_data() + camera_data = CameraData() + camera_data.info = {} + camera_data.output = {} + + result = renderer.read_output(render_data, camera_data) + assert result is None + assert render_data.warp_buffers == {} + assert camera_data.info == {} + assert camera_data.output == {} diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py index c9c34385266b..ff5a36491adf 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py @@ -22,7 +22,7 @@ from pxr import Sdf from isaaclab.app.settings_manager import get_settings_manager -from isaaclab.renderers import BaseRenderer, CameraDataType, OutputSpec +from isaaclab.renderers import BaseRenderer, RenderBufferKind, RenderBufferSpec from isaaclab.utils.version import get_isaac_sim_version from isaaclab.utils.warp.kernels import reshape_tiled_image @@ -95,40 +95,40 @@ def __init__(self, cfg: IsaacRtxRendererCfg): ensure_rtx_hydra_engine_attached() # ``/isaaclab/render/rtx_sensors`` is owned by ``Camera.__init__`` (must be set pre-``sim.reset()``). - def supported_output_types(self) -> dict[CameraDataType, OutputSpec]: + def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Publish the per-output Replicator layout this RTX backend writes. ``ALBEDO`` and the three ``SIMPLE_SHADING_*`` outputs require Isaac Sim 6.0+ and are omitted on older versions. The three segmentation outputs report - ``OutputSpec(4, uint8)`` when the matching ``self.cfg.colorize_*`` flag is - set, otherwise ``OutputSpec(1, int32)``. + ``RenderBufferSpec(4, uint8)`` when the matching ``self.cfg.colorize_*`` flag is + set, otherwise ``RenderBufferSpec(1, int32)``. """ sim_major = get_isaac_sim_version().major - specs: dict[CameraDataType, OutputSpec] = { + specs: dict[RenderBufferKind, RenderBufferSpec] = { # Replicator's native layout for color output is rgba/uint8; # ``Camera`` aliases ``rgb`` as a view into ``rgba`` storage. - CameraDataType.RGBA: OutputSpec(4, torch.uint8), - CameraDataType.RGB: OutputSpec(3, torch.uint8), - CameraDataType.DEPTH: OutputSpec(1, torch.float32), - CameraDataType.DISTANCE_TO_IMAGE_PLANE: OutputSpec(1, torch.float32), - CameraDataType.DISTANCE_TO_CAMERA: OutputSpec(1, torch.float32), - CameraDataType.NORMALS: OutputSpec(3, torch.float32), - CameraDataType.MOTION_VECTORS: OutputSpec(2, torch.float32), + RenderBufferKind.RGBA: RenderBufferSpec(4, torch.uint8), + RenderBufferKind.RGB: RenderBufferSpec(3, torch.uint8), + RenderBufferKind.DEPTH: RenderBufferSpec(1, torch.float32), + RenderBufferKind.DISTANCE_TO_IMAGE_PLANE: RenderBufferSpec(1, torch.float32), + RenderBufferKind.DISTANCE_TO_CAMERA: RenderBufferSpec(1, torch.float32), + RenderBufferKind.NORMALS: RenderBufferSpec(3, torch.float32), + RenderBufferKind.MOTION_VECTORS: RenderBufferSpec(2, torch.float32), } if sim_major >= 6: - specs[CameraDataType.ALBEDO] = OutputSpec(4, torch.uint8) + specs[RenderBufferKind.ALBEDO] = RenderBufferSpec(4, torch.uint8) for shading_type in SIMPLE_SHADING_MODES: - specs[CameraDataType(shading_type)] = OutputSpec(3, torch.uint8) + specs[RenderBufferKind(shading_type)] = RenderBufferSpec(3, torch.uint8) seg_specs = ( - (CameraDataType.SEMANTIC_SEGMENTATION, self.cfg.colorize_semantic_segmentation), - (CameraDataType.INSTANCE_SEGMENTATION_FAST, self.cfg.colorize_instance_segmentation), - (CameraDataType.INSTANCE_ID_SEGMENTATION_FAST, self.cfg.colorize_instance_id_segmentation), + (RenderBufferKind.SEMANTIC_SEGMENTATION, self.cfg.colorize_semantic_segmentation), + (RenderBufferKind.INSTANCE_SEGMENTATION_FAST, self.cfg.colorize_instance_segmentation), + (RenderBufferKind.INSTANCE_ID_SEGMENTATION_FAST, self.cfg.colorize_instance_id_segmentation), ) for name, colorize in seg_specs: - specs[name] = OutputSpec(4, torch.uint8) if colorize else OutputSpec(1, torch.int32) + specs[name] = RenderBufferSpec(4, torch.uint8) if colorize else RenderBufferSpec(1, torch.int32) return specs diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py index 15043c6a2aa0..de5d433e867f 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_cfg.py @@ -59,7 +59,7 @@ class IsaacRtxRendererCfg(RendererCfg): """ colorize_instance_segmentation: bool = True - """Whether to colorize the instance ID segmentation images. Defaults to True. + """Whether to colorize the instance segmentation images. Defaults to True. If True, instance segmentation is converted to an image where instance IDs are mapped to colors. and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array. @@ -88,5 +88,5 @@ class IsaacRtxRendererCfg(RendererCfg): - ``"max"``: Values are clipped to the maximum value. - ``"zero"``: Values are clipped to zero. - - ``"none``: No clipping is applied. Values will be returned as ``inf``. + - ``"none"``: No clipping is applied. Values will be returned as ``inf``. """