From 0733322b7c5506b537b910b184966f493331d249 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 2 Apr 2026 17:06:54 -0700 Subject: [PATCH 1/4] Move TiledCamera implementation into Camera --- .../isaaclab/sensors/camera/camera.py | 414 ++++++------------ .../isaaclab/sensors/camera/tiled_camera.py | 363 +-------------- .../sensors/camera/tiled_camera_cfg.py | 15 +- .../renderers/isaac_rtx_renderer.py | 39 +- 4 files changed, 194 insertions(+), 637 deletions(-) diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 70ccc6c14dd8..54f47c14d69c 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -5,10 +5,9 @@ from __future__ import annotations -import json import logging from collections.abc import Sequence -from typing import TYPE_CHECKING, Any, Literal +from typing import TYPE_CHECKING, Literal import numpy as np import torch @@ -20,9 +19,9 @@ 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 Renderer from isaaclab.sim.views import XformPrimView from isaaclab.utils import has_kit, to_camel_case -from isaaclab.utils.array import convert_to_torch from isaaclab.utils.math import ( convert_camera_frame_orientation_convention, create_rotation_matrix_from_view, @@ -96,13 +95,11 @@ class Camera(SensorBase): } """The set of sensor types that are not supported by the camera class.""" - SIMPLE_SHADING_MODES: dict[str, int] = { - "simple_shading_constant_diffuse": 0, - "simple_shading_diffuse_mdl": 1, - "simple_shading_full_mdl": 2, + SIMPLE_SHADING_TYPES: set[str] = { + "simple_shading_constant_diffuse", + "simple_shading_diffuse_mdl", + "simple_shading_full_mdl", } - SIMPLE_SHADING_AOV: str = "SimpleShadingSD" - SIMPLE_SHADING_MODE_SETTING: str = "/rtx/sdg/simpleShading/mode" def __init__(self, cfg: CameraCfg): """Initializes the camera sensor. @@ -124,34 +121,6 @@ def __init__(self, cfg: CameraCfg): settings = get_settings_manager() settings.set_bool("/isaaclab/render/rtx_sensors", True) - # This is only introduced in isaac sim 6.0 - if has_kit(): - isaac_sim_version = get_isaac_sim_version() - if isaac_sim_version.major >= 6: - # Set RTX flag to enable fast path when no regular RGB/RGBA annotators are requested - needs_color_render = "rgb" in self.cfg.data_types or "rgba" in self.cfg.data_types - if not needs_color_render: - settings.set_bool("/rtx/sdg/force/disableColorRender", True) - - # If we have GUI / viewport enabled, we turn off fast path so that the viewport is not black - if settings.get("/isaaclab/has_gui"): - settings.set_bool("/rtx/sdg/force/disableColorRender", False) - else: - if "albedo" in self.cfg.data_types: - logger.warning( - "Albedo annotator is only supported in Isaac Sim 6.0+. The albedo data type will be ignored." - ) - if any(data_type in self.SIMPLE_SHADING_MODES for data_type in self.cfg.data_types): - logger.warning( - "Simple shading annotators are only supported in Isaac Sim 6.0+. The simple shading data types" - " will be ignored." - ) - - # Set simple shading mode (if requested) before rendering - simple_shading_mode = self._resolve_simple_shading_mode() - if simple_shading_mode is not None: - settings.set_int(self.SIMPLE_SHADING_MODE_SETTING, simple_shading_mode) - # spawn the asset if self.cfg.spawn is not None: # Use spawn_path when set (points to template location for scene-cloned sensors). @@ -187,6 +156,9 @@ def __init__(self, cfg: CameraCfg): self._sensor_prims: list[UsdGeom.Camera] = list() # Create empty variables for storing output data self._data = CameraData() + # Renderer and render data — initialized in _initialize_impl + self.renderer: Renderer | None = None + self.render_data = None if not has_kit(): return @@ -205,14 +177,12 @@ def __init__(self, cfg: CameraCfg): prim.SetInstanceable(False) def __del__(self): - """Unsubscribes from callbacks and detach from the replicator registry.""" + """Unsubscribes from callbacks and cleans up renderer resources.""" # unsubscribe callbacks super().__del__() - # delete from replicator registry - for _, annotators in self._rep_registry.items(): - for annotator, render_product_path in zip(annotators, self._render_product_paths): - annotator.detach([render_product_path]) - annotator = None + # cleanup render resources (renderer may be None if never initialized) + if hasattr(self, "renderer") and self.renderer is not None: + self.renderer.cleanup(getattr(self, "render_data", None)) def __str__(self) -> str: """Returns: A string containing information about the instance.""" @@ -249,14 +219,6 @@ def frame(self) -> torch.tensor: """Frame number when the measurement took place.""" return self._frame - @property - def render_product_paths(self) -> list[str]: - """The path of the render products for the cameras. - - This can be used via replicator interfaces to attach to writes or external annotator registry. - """ - return self._render_product_paths - @property def image_shape(self) -> tuple[int, int]: """A tuple containing (height, width) of the camera sensor.""" @@ -428,12 +390,13 @@ def reset(self, env_ids: Sequence[int] | None = None, env_mask: wp.array | None def _initialize_impl(self): """Initializes the sensor handles and internal buffers. - This function creates handles and registers the provided data types with the replicator registry to - be able to access the data from the sensor. It also initializes the internal buffers to store the data. + This function creates a :class:`~isaaclab.renderers.Renderer` from the configured + :attr:`~isaaclab.sensors.camera.CameraCfg.renderer_cfg` and delegates all render-product + and annotator management to it. It also initializes the internal buffers to store the data. Raises: RuntimeError: If the number of camera prims in the view does not match the number of environments. - RuntimeError: If replicator was not found. + RuntimeError: If cameras are not enabled (missing ``--enable_cameras`` flag). """ renderer_type = getattr(self.cfg.renderer_cfg, "renderer_type", "default") needs_kit_cameras = renderer_type in ("default", "isaac_rtx") @@ -443,12 +406,19 @@ def _initialize_impl(self): " rendering." ) - import omni.replicator.core as rep - from omni.syntheticdata.scripts.SyntheticData import SyntheticData - # Initialize parent class super()._initialize_impl() - # Create a view for the sensor with Fabric enabled for fast pose queries, otherwise position will be stale. + + self.renderer = Renderer(self.cfg.renderer_cfg) + logger.info("Using renderer: %s", type(self.renderer).__name__) + + # Stage preprocessing must happen before creating the view because the view keeps + # references to prims located in the stage. + self.renderer.prepare_stage(self.stage, self._num_envs) + + # Create a view for the sensor with Fabric enabled for fast pose queries. + # TODO: remove sync_usd_on_fabric_write=True once the GPU (cuda:0) Fabric sync bug in + # renderer.update_transforms() is fixed. Without it, poses are stale on the GPU path. self._view = XformPrimView( self.cfg.prim_path, device=self._device, stage=self.stage, sync_usd_on_fabric_write=True ) @@ -464,10 +434,6 @@ def _initialize_impl(self): # Create frame count buffer self._frame = torch.zeros(self._view.count, device=self._device, dtype=torch.long) - # Attach the sensor data types to render node - self._render_product_paths: list[str] = list() - self._rep_registry: dict[str, list[rep.annotators.Annotator]] = {name: list() for name in self.cfg.data_types} - # Convert all encapsulated prims to Camera for cam_prim in self._view.prims: # Obtain the prim path @@ -476,84 +442,13 @@ def _initialize_impl(self): if not cam_prim.IsA(UsdGeom.Camera): raise RuntimeError(f"Prim at path '{cam_prim_path}' is not a Camera.") # Add to list - sensor_prim = UsdGeom.Camera(cam_prim) - self._sensor_prims.append(sensor_prim) - - # Get render product - # From Isaac Sim 2023.1 onwards, render product is a HydraTexture so we need to extract the path - render_prod_path = rep.create.render_product(cam_prim_path, resolution=(self.cfg.width, self.cfg.height)) - if not isinstance(render_prod_path, str): - render_prod_path = render_prod_path.path - self._render_product_paths.append(render_prod_path) - - # Check if semantic types or semantic filter predicate is provided - if isinstance(self.cfg.semantic_filter, list): - semantic_filter_predicate = ":*; ".join(self.cfg.semantic_filter) + ":*" - elif isinstance(self.cfg.semantic_filter, str): - semantic_filter_predicate = self.cfg.semantic_filter - else: - raise ValueError(f"Semantic types must be a list or a string. Received: {self.cfg.semantic_filter}.") - # set the semantic filter predicate - # copied from rep.scripts.writes_default.basic_writer.py - SyntheticData.Get().set_instance_mapping_semantic_filter(semantic_filter_predicate) - - # Iterate over each data type and create annotator - # TODO: This will move out of the loop once Replicator supports multiple render products within a single - # annotator, i.e.: rep_annotator.attach(self._render_product_paths) - for name in self.cfg.data_types: - # note: we are verbose here to make it easier to understand the code. - # if colorize is true, the data is mapped to colors and a uint8 4 channel image is returned. - # if colorize is false, the data is returned as a uint32 image with ids as values. - if name == "semantic_segmentation": - init_params = { - "colorize": self.cfg.colorize_semantic_segmentation, - "mapping": json.dumps(self.cfg.semantic_segmentation_mapping), - } - elif name == "instance_segmentation_fast": - init_params = {"colorize": self.cfg.colorize_instance_segmentation} - elif name == "instance_id_segmentation_fast": - init_params = {"colorize": self.cfg.colorize_instance_id_segmentation} - else: - init_params = None - - # Resolve device name - if "cuda" in self._device: - device_name = self._device.split(":")[0] - else: - device_name = "cpu" - - # TODO: this is a temporary solution because replicator has not exposed the annotator yet - # once it's exposed, we can remove this - if name == "albedo": - rep.AnnotatorRegistry.register_annotator_from_aov( - aov="DiffuseAlbedoSD", output_data_type=np.uint8, output_channels=4 - ) - if name in self.SIMPLE_SHADING_MODES: - rep.AnnotatorRegistry.register_annotator_from_aov( - aov=self.SIMPLE_SHADING_AOV, output_data_type=np.uint8, output_channels=4 - ) - - # Map special cases to their corresponding annotator names - simple_shading_cases = {key: self.SIMPLE_SHADING_AOV for key in self.SIMPLE_SHADING_MODES} - special_cases = { - "rgba": "rgb", - "depth": "distance_to_image_plane", - "albedo": "DiffuseAlbedoSD", - **simple_shading_cases, - } - # Get the annotator name, falling back to the original name if not a special case - annotator_name = special_cases.get(name, name) - # Create the annotator node - rep_annotator = rep.AnnotatorRegistry.get_annotator(annotator_name, init_params, device=device_name) - - # attach annotator to render product - rep_annotator.attach(render_prod_path) - # add to registry - self._rep_registry[name].append(rep_annotator) - - # Create internal buffers + self._sensor_prims.append(UsdGeom.Camera(cam_prim)) + + # View needs to exist before creating render data + self.render_data = self.renderer.create_render_data(self) + + # Create internal buffers (includes intrinsic matrix and pose init) self._create_buffers() - self._update_intrinsic_matrices(self._ALL_INDICES) def _update_buffers_impl(self, env_mask: wp.array): env_ids = wp.to_torch(env_mask).nonzero(as_tuple=False).squeeze(-1) @@ -561,50 +456,24 @@ def _update_buffers_impl(self, env_mask: wp.array): return # Increment frame count self._frame[env_ids] += 1 - # -- pose + # update latest camera pose if requested if self.cfg.update_latest_camera_pose: self._update_poses(env_ids) - # Ensure the RTX renderer has been pumped so annotator buffers are fresh. - # Lazy import Isaac RTX Renderer dependency. - # For now the Camera implementation works only with Isaac RTX Renderer. - # Future consideration should be to move Renderer from TiledCamera up the hierarchy to Camera - # to make the Camera backend-agnostic. - from isaaclab_physx.renderers.isaac_rtx_renderer_utils import ensure_isaac_rtx_render_update - - ensure_isaac_rtx_render_update() - - # -- read the data from annotator registry - # check if buffer is called for the first time. If so then, allocate the memory - if len(self._data.output) == 0: - # this is the first time buffer is called - # it allocates memory for all the sensors - self._create_annotator_data() - else: - # iterate over all the data types - for name, annotators in self._rep_registry.items(): - # iterate over all the annotators - for index in env_ids: - # get the output - output = annotators[index].get_data() - # process the output - data, info = self._process_annotator_output(name, output) - # add data to output - self._data.output[name][index] = data - # add info to output - self._data.info[index][name] = info - # NOTE: The `distance_to_camera` annotator returns the distance to the camera optical center. However, - # the replicator depth clipping is applied w.r.t. to the image plane which may result in values - # larger than the clipping range in the output. We apply an additional clipping to ensure values - # are within the clipping range for all the annotators. - if name == "distance_to_camera": - self._data.output[name][self._data.output[name] > self.cfg.spawn.clipping_range[1]] = torch.inf - # apply defined clipping behavior - if ( - name == "distance_to_camera" or name == "distance_to_image_plane" - ) and self.cfg.depth_clipping_behavior != "none": - self._data.output[name][torch.isinf(self._data.output[name])] = ( - 0.0 if self.cfg.depth_clipping_behavior == "zero" else self.cfg.spawn.clipping_range[1] - ) + + self.renderer.update_transforms() + self.renderer.render(self.render_data) + + for output_name, output_data in self._data.output.items(): + if output_name == "rgb": + continue + self.renderer.write_output(self.render_data, output_name, output_data) + + # Broadcast renderer info (e.g. segmentation label mappings) to all per-camera entries + renderer_info = getattr(self.render_data, "renderer_info", None) + if renderer_info: + for data_type, metadata in renderer_info.items(): + for cam_idx in range(self._view.count): + self._data.info[cam_idx][data_type] = metadata """ Private Helpers @@ -632,19 +501,82 @@ def _check_supported_data_types(self, cfg: CameraCfg): def _create_buffers(self): """Create buffers for storing data.""" - # create the data object + # -- 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) - # -- intrinsic matrix - self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device) + self._update_poses(self._ALL_INDICES) self._data.image_shape = self.image_shape - # -- output data - # lazy allocation of data dictionary - # since the size of the output data is not known in advance, we leave it as None - # the memory will be allocated when the buffer() function is called for the first time. - self._data.output = {} + # -- 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} for _ in range(self._view.count)] + self.renderer.set_outputs(self.render_data, self._data.output) def _update_intrinsic_matrices(self, env_ids: Sequence[int]): """Compute camera's matrix of intrinsic parameters. @@ -697,107 +629,11 @@ def _update_poses(self, env_ids: Sequence[int]): self._data.quat_w_world[env_ids] = convert_camera_frame_orientation_convention( quat, origin="opengl", target="world" ) - - def _create_annotator_data(self): - """Create the buffers to store the annotator data. - - We create a buffer for each annotator and store the data in a dictionary. Since the data - shape is not known beforehand, we create a list of buffers and concatenate them later. - - This is an expensive operation and should be called only once. - """ - # add data from the annotators - for name, annotators in self._rep_registry.items(): - # create a list to store the data for each annotator - data_all_cameras = list() - # iterate over all the annotators - for index in self._ALL_INDICES: - # get the output - output = annotators[index].get_data() - # process the output - data, info = self._process_annotator_output(name, output) - # append the data - data_all_cameras.append(data) - # store the info - self._data.info[index][name] = info - # concatenate the data along the batch dimension - self._data.output[name] = torch.stack(data_all_cameras, dim=0) - # NOTE: `distance_to_camera` and `distance_to_image_plane` are not both clipped to the maximum defined - # in the clipping range. The clipping is applied only to `distance_to_image_plane` and then both - # outputs are only clipped where the values in `distance_to_image_plane` exceed the threshold. To - # have a unified behavior between all cameras, we clip both outputs to the maximum value defined. - if name == "distance_to_camera": - self._data.output[name][self._data.output[name] > self.cfg.spawn.clipping_range[1]] = torch.inf - # clip the data if needed - if ( - name == "distance_to_camera" or name == "distance_to_image_plane" - ) and self.cfg.depth_clipping_behavior != "none": - self._data.output[name][torch.isinf(self._data.output[name])] = ( - 0.0 if self.cfg.depth_clipping_behavior == "zero" else self.cfg.spawn.clipping_range[1] - ) - - def _process_annotator_output(self, name: str, output: Any) -> tuple[torch.tensor, dict | None]: - """Process the annotator output. - - This function is called after the data has been collected from all the cameras. - """ - # extract info and data from the output - if isinstance(output, dict): - data = output["data"] - info = output["info"] - else: - data = output - info = None - # convert data into torch tensor - data = convert_to_torch(data, device=self.device) - - # process data for different segmentation types - # Note: Replicator returns raw buffers of dtype int32 for segmentation types - # so we need to convert them to uint8 4 channel images for colorized types - height, width = self.image_shape - if name == "semantic_segmentation": - if self.cfg.colorize_semantic_segmentation: - data = data.view(torch.uint8).reshape(height, width, -1) - else: - data = data.view(height, width, 1) - elif name == "instance_segmentation_fast": - if self.cfg.colorize_instance_segmentation: - data = data.view(torch.uint8).reshape(height, width, -1) - else: - data = data.view(height, width, 1) - elif name == "instance_id_segmentation_fast": - if self.cfg.colorize_instance_id_segmentation: - data = data.view(torch.uint8).reshape(height, width, -1) - else: - data = data.view(height, width, 1) - # make sure buffer dimensions are consistent as (H, W, C) - elif name == "distance_to_camera" or name == "distance_to_image_plane" or name == "depth": - data = data.view(height, width, 1) - # we only return the RGB channels from the RGBA output if rgb is required - # normals return (x, y, z) in first 3 channels, 4th channel is unused - elif name == "rgb" or name == "normals": - data = data[..., :3] - # motion vectors return (x, y) in first 2 channels, 3rd and 4th channels are unused - elif name == "motion_vectors": - data = data[..., :2] - elif name in self.SIMPLE_SHADING_MODES: - data = data[..., :3] - - # return the data and info - return data, info - - def _resolve_simple_shading_mode(self) -> int | None: - """Resolve the requested simple shading mode from data types.""" - requested = [data_type for data_type in self.cfg.data_types if data_type in self.SIMPLE_SHADING_MODES] - if not requested: - return None - if len(requested) > 1: - logger.warning( - "Multiple simple shading modes requested (%s). Using '%s' only.", - requested, - requested[0], + # notify renderer of updated poses (guarded in case called before initialization completes) + if self.render_data is not None: + self.renderer.update_camera( + self.render_data, self._data.pos_w, self._data.quat_w_world, self._data.intrinsic_matrices ) - return self.SIMPLE_SHADING_MODES[requested[0]] """ Internal simulation callbacks. diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py index e6ae56adaa53..3c2b1aaf80e5 100644 --- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py @@ -3,359 +3,34 @@ # # SPDX-License-Identifier: BSD-3-Clause -from __future__ import annotations - -import logging -import math -from collections.abc import Sequence -from typing import TYPE_CHECKING, Any +"""Deprecated module. Use :class:`~isaaclab.sensors.camera.Camera` instead. -import torch -import warp as wp +.. deprecated:: 4.5.26 + :class:`TiledCamera` is deprecated. :class:`~isaaclab.sensors.camera.Camera` now uses the same + :class:`~isaaclab.renderers.Renderer` abstraction. Use :class:`~isaaclab.sensors.camera.Camera` + with :class:`~isaaclab.sensors.camera.CameraCfg` (or :class:`~isaaclab.sensors.camera.TiledCameraCfg`) + directly. +""" -from pxr import UsdGeom +from __future__ import annotations -from isaaclab.app.settings_manager import get_settings_manager -from isaaclab.renderers import Renderer -from isaaclab.sim.views import XformPrimView +import warnings -from ..sensor_base import SensorBase from .camera import Camera -logger = logging.getLogger(__name__) - -if TYPE_CHECKING: - from isaaclab.renderers import Renderer - - from .tiled_camera_cfg import TiledCameraCfg - class TiledCamera(Camera): - SIMPLE_SHADING_AOV: str = "SimpleShadingSD" - r"""The tiled rendering based camera sensor for acquiring the same data as the Camera class. - - This class inherits from the :class:`Camera` class but uses the tiled-rendering API to acquire - the visual data. Tiled-rendering concatenates the rendered images from multiple cameras into a single image. - This allows for rendering multiple cameras in parallel and is useful for rendering large scenes with multiple - cameras efficiently. - - The following sensor types are supported: - - - ``"rgb"``: A 3-channel rendered color image. - - ``"rgba"``: A 4-channel rendered color image with alpha channel. - - ``"albedo"``: A 4-channel fast diffuse-albedo only path for color image. - Note that this path will achieve the best performance when used alone or with depth only. - - ``"distance_to_camera"``: An image containing the distance to camera optical center. - - ``"distance_to_image_plane"``: An image containing distances of 3D points from camera plane along camera's z-axis. - - ``"depth"``: Alias for ``"distance_to_image_plane"``. - - ``"simple_shading_constant_diffuse"``: Simple shading (constant diffuse) RGB approximation. - - ``"simple_shading_diffuse_mdl"``: Simple shading (diffuse MDL) RGB approximation. - - ``"simple_shading_full_mdl"``: Simple shading (full MDL) RGB approximation. - - ``"normals"``: An image containing the local surface normal vectors at each pixel. - - ``"motion_vectors"``: An image containing the motion vector data at each pixel. - - ``"semantic_segmentation"``: The semantic segmentation data. - - ``"instance_segmentation_fast"``: The instance segmentation data. - - ``"instance_id_segmentation_fast"``: The instance id segmentation data. - - .. note:: - Currently the following sensor types are not supported in a "view" format: - - - ``"instance_segmentation"``: The instance segmentation data. Please use the fast counterparts instead. - - ``"instance_id_segmentation"``: The instance id segmentation data. Please use the fast counterparts instead. - - ``"bounding_box_2d_tight"``: The tight 2D bounding box data (only contains non-occluded regions). - - ``"bounding_box_2d_tight_fast"``: The tight 2D bounding box data (only contains non-occluded regions). - - ``"bounding_box_2d_loose"``: The loose 2D bounding box data (contains occluded regions). - - ``"bounding_box_2d_loose_fast"``: The loose 2D bounding box data (contains occluded regions). - - ``"bounding_box_3d"``: The 3D view space bounding box data. - - ``"bounding_box_3d_fast"``: The 3D view space bounding box data. - - .. _replicator extension: https://docs.omniverse.nvidia.com/extensions/latest/ext_replicator/annotators_details.html#annotator-output - .. _USDGeom Camera: https://graphics.pixar.com/usd/docs/api/class_usd_geom_camera.html - - .. versionadded:: v1.0.0 - - This feature is available starting from Isaac Sim 4.2. Before this version, the tiled rendering APIs - were not available. + """Deprecated alias for :class:`Camera`. + .. deprecated:: 4.5.26 + Use :class:`Camera` directly — it now uses the same Renderer abstraction. """ - cfg: TiledCameraCfg - """The configuration parameters.""" - - def __init__(self, cfg: TiledCameraCfg): - """Initializes the tiled camera sensor. - - Args: - cfg: The configuration parameters. - - Raises: - RuntimeError: If no camera prim is found at the given path. - ValueError: If the provided data types are not supported by the camera. - """ - self.renderer: Renderer | None = None - self.render_data = None - super().__init__(cfg) - - def __del__(self): - """Unsubscribes from callbacks and detach from the replicator registry.""" - # unsubscribe from callbacks - SensorBase.__del__(self) - # cleanup render resources (renderer may be None if never initialized) - if hasattr(self, "renderer") and self.renderer is not None: - self.renderer.cleanup(getattr(self, "render_data", None)) - - def __str__(self) -> str: - """Returns: A string containing information about the instance.""" - # message for class - return ( - f"Tiled 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}" + def __init__(self, cfg): + warnings.warn( + "TiledCamera is deprecated and will be removed in a future release. " + "Use Camera directly — it now uses the same Renderer abstraction.", + DeprecationWarning, + stacklevel=2, ) - - """ - Operations - """ - - def reset(self, env_ids: Sequence[int] | None = None, env_mask: wp.array | None = None): - if not self._is_initialized: - raise RuntimeError( - "TiledCamera could not be initialized. Please ensure --enable_cameras is used to enable rendering." - ) - # reset the timestamps - SensorBase.reset(self, env_ids, env_mask) - # resolve to indices for torch indexing - if env_ids is None and env_mask is not None: - env_ids = wp.to_torch(env_mask).nonzero(as_tuple=False).squeeze(-1) - elif env_ids is None: - env_ids = slice(None) - # reset the frame count - self._frame[env_ids] = 0 - - """ - Implementation. - """ - - def _initialize_impl(self): - """Initializes the sensor handles and internal buffers. - - This function creates handles and registers the provided data types with the renderer to - be able to access the data from the sensor. It also initializes the internal buffers to store the data. - - Raises: - RuntimeError: If the number of camera prims in the view does not match the number of environments. - RuntimeError: If replicator was not found. - """ - 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 - SensorBase._initialize_impl(self) - - self.renderer = Renderer(self.cfg.renderer_cfg) - logger.info("Using renderer: %s", type(self.renderer).__name__) - - # Stage preprocessing needs to happen before creating the view because - # the view keeps references to the prims located in the stage - self.renderer.prepare_stage(self.stage, self._num_envs) - - # Create a view for the sensor - self._view = XformPrimView(self.cfg.prim_path, device=self._device, stage=self.stage) - # Check that sizes are correct - if self._view.count != self._num_envs: - raise RuntimeError( - f"Number of camera prims in the view ({self._view.count}) does not match" - f" the number of environments ({self._num_envs})." - ) - - # Create all env_ids buffer - self._ALL_INDICES = torch.arange(self._view.count, device=self._device, dtype=torch.long) - # Create frame count buffer - self._frame = torch.zeros(self._view.count, device=self._device, dtype=torch.long) - - # Convert all encapsulated prims to Camera - for cam_prim in self._view.prims: - # Get camera prim - cam_prim_path = cam_prim.GetPath().pathString - # Check if prim is a camera - if not cam_prim.IsA(UsdGeom.Camera): - raise RuntimeError(f"Prim at path '{cam_prim_path}' is not a Camera.") - # Add to list - self._sensor_prims.append(UsdGeom.Camera(cam_prim)) - - # View needs to exist before creating render data - self.render_data = self.renderer.create_render_data(self) - - # Create internal buffers - self._create_buffers() - - def _update_poses(self, env_ids: Sequence[int]): - super()._update_poses(env_ids) - self.renderer.update_camera( - self.render_data, self._data.pos_w, self._data.quat_w_world, self._data.intrinsic_matrices - ) - - def _update_buffers_impl(self, env_mask: wp.array): - env_ids = wp.to_torch(env_mask).nonzero(as_tuple=False).squeeze(-1) - if len(env_ids) == 0: - return - # Increment frame count - self._frame[env_ids] += 1 - - # update latest camera pose - if self.cfg.update_latest_camera_pose: - self._update_poses(env_ids) - - self.renderer.update_transforms() - self.renderer.render(self.render_data) - - for output_name, output_data in self._data.output.items(): - if output_name == "rgb": - continue - self.renderer.write_output(self.render_data, output_name, output_data) - - """ - Private Helpers - """ - - def _check_supported_data_types(self, cfg: TiledCameraCfg): - """Checks if the data types are supported by the ray-caster camera.""" - # check if there is any intersection in unsupported types - # reason: these use np structured data types which we can't yet convert to torch tensor - common_elements = set(cfg.data_types) & Camera.UNSUPPORTED_TYPES - if common_elements: - # provide alternative fast counterparts - fast_common_elements = [] - for item in common_elements: - if "instance_segmentation" in item or "instance_id_segmentation" in item: - fast_common_elements.append(item + "_fast") - # raise error - raise ValueError( - f"TiledCamera class does not support the following sensor types: {common_elements}." - "\n\tThis is because these sensor types output numpy structured data types which" - "can't be converted to torch tensors easily." - "\n\tHint: If you need to work with these sensor types, we recommend using their fast counterparts." - f"\n\t\tFast counterparts: {fast_common_elements}" - ) - - def _create_buffers(self): - """Create buffers for storing data.""" - # create the data object - # -- 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 - 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: - # RGB is the first 3 channels of RGBA - 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_MODES: - 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 = dict() - self.renderer.set_outputs(self.render_data, self._data.output) - - def _tiled_image_shape(self) -> tuple[int, int]: - """Returns a tuple containing the dimension of the tiled image.""" - cols, rows = self._tiling_grid_shape() - return (self.cfg.width * cols, self.cfg.height * rows) - - def _tiling_grid_shape(self) -> tuple[int, int]: - """Returns a tuple containing the tiling grid dimension.""" - cols = math.ceil(math.sqrt(self._view.count)) - rows = math.ceil(self._view.count / cols) - return (cols, rows) - - def _create_annotator_data(self): - # we do not need to create annotator data for the tiled camera sensor - raise RuntimeError("This function should not be called for the tiled camera sensor.") - - def _process_annotator_output(self, name: str, output: Any) -> tuple[torch.tensor, dict | None]: - # we do not need to process annotator output for the tiled camera sensor - raise RuntimeError("This function should not be called for the tiled camera sensor.") - - """ - Internal simulation callbacks. - """ - - def _invalidate_initialize_callback(self, event): - """Invalidates the scene elements.""" - # call parent - super()._invalidate_initialize_callback(event) - # set all existing views to None to invalidate them - self._view = None + super().__init__(cfg) diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py index c0613406ef3e..53021825d26e 100644 --- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py @@ -3,6 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause +import warnings from typing import TYPE_CHECKING from isaaclab.utils import configclass @@ -15,6 +16,18 @@ @configclass class TiledCameraCfg(CameraCfg): - """Configuration for a tiled rendering-based camera sensor.""" + """Configuration for a tiled rendering-based camera sensor. + + .. deprecated:: 4.5.26 + :class:`TiledCameraCfg` is deprecated. Use :class:`CameraCfg` directly — + :class:`~isaaclab.sensors.camera.Camera` now uses the same renderer abstraction. + """ class_type: type["TiledCamera"] | str = "{DIR}.tiled_camera:TiledCamera" + + def __post_init__(self): + warnings.warn( + "TiledCameraCfg is deprecated. Use CameraCfg directly.", + DeprecationWarning, + stacklevel=2, + ) 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 22b07f13def0..91f14c689da5 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py @@ -8,6 +8,7 @@ from __future__ import annotations import json +import logging import math import weakref from dataclasses import dataclass @@ -19,16 +20,19 @@ from isaaclab.app.settings_manager import get_settings_manager from isaaclab.renderers import BaseRenderer +from isaaclab.utils.version import get_isaac_sim_version from isaaclab.utils.warp.kernels import reshape_tiled_image from .isaac_rtx_renderer_utils import ensure_isaac_rtx_render_update +logger = logging.getLogger(__name__) + if TYPE_CHECKING: from isaaclab.sensors import SensorBase from .isaac_rtx_renderer_cfg import IsaacRtxRendererCfg -# Constants from Camera (SIMPLE_SHADING_MODES, etc.) - avoid circular import +# RTX simple-shading constants (mode indices, AOV name, carb setting path) SIMPLE_SHADING_AOV = "SimpleShadingSD" SIMPLE_SHADING_MODES = { "simple_shading_constant_diffuse": 0, @@ -46,6 +50,7 @@ class IsaacRtxRenderData: render_product_paths: list[str] output_data: dict[str, torch.Tensor] | None = None sensor: SensorBase | None = None + renderer_info: dict[str, Any] | None = None class IsaacRtxRenderer(BaseRenderer): @@ -68,6 +73,26 @@ def create_render_data(self, sensor: SensorBase) -> IsaacRtxRenderData: import omni.replicator.core as rep from pxr import UsdGeom + settings = get_settings_manager() + isaac_sim_version = get_isaac_sim_version() + + if isaac_sim_version.major >= 6: + needs_color_render = "rgb" in sensor.cfg.data_types or "rgba" in sensor.cfg.data_types + if not needs_color_render: + settings.set_bool("/rtx/sdg/force/disableColorRender", True) + if settings.get("/isaaclab/has_gui"): + settings.set_bool("/rtx/sdg/force/disableColorRender", False) + else: + if "albedo" in sensor.cfg.data_types: + logger.warning( + "Albedo annotator is only supported in Isaac Sim 6.0+. The albedo data type will be ignored." + ) + if any(dt in SIMPLE_SHADING_MODES for dt in sensor.cfg.data_types): + logger.warning( + "Simple shading annotators are only supported in Isaac Sim 6.0+." + " The simple shading data types will be ignored." + ) + # Get camera prim paths from sensor view view = sensor._view cam_prim_paths = [] @@ -159,6 +184,12 @@ def _resolve_simple_shading_mode(self, sensor: SensorBase) -> int | None: requested = [dt for dt in sensor.cfg.data_types if dt in SIMPLE_SHADING_MODES] if not requested: return None + if len(requested) > 1: + logger.warning( + "Multiple simple shading modes requested (%s). Using '%s' only.", + requested, + requested[0], + ) return SIMPLE_SHADING_MODES[requested[0]] def set_outputs(self, render_data: IsaacRtxRenderData, output_data: dict[str, torch.Tensor]): @@ -205,14 +236,16 @@ def tiling_grid_shape(): num_tiles_x = tiling_grid_shape()[0] + if render_data.renderer_info is None: + render_data.renderer_info = {} + # Extract the flattened image buffer for data_type, annotator in render_data.annotators.items(): # check whether returned data is a dict (used for segmentation) output = annotator.get_data() if isinstance(output, dict): tiled_data_buffer = output["data"] - if hasattr(sensor, "_data") and sensor._data is not None: - sensor._data.info[data_type] = output["info"] + render_data.renderer_info[data_type] = output["info"] else: tiled_data_buffer = output From 2dafbd7add1becf898764223ee24dd59a62be5ee Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 2 Apr 2026 20:45:59 -0700 Subject: [PATCH 2/4] Align test suite with camera refactoring --- source/isaaclab/test/sensors/test_camera.py | 283 +++ .../test/sensors/test_multi_tiled_camera.py | 10 +- .../test/sensors/test_tiled_camera.py | 1675 +---------------- 3 files changed, 343 insertions(+), 1625 deletions(-) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index f1effb9a70e7..e314b608bc98 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -797,6 +797,289 @@ def test_sensor_print(setup_sim_camera): print(sensor) +def setup_with_device(device) -> tuple[sim_utils.SimulationContext, CameraCfg, float]: + camera_cfg = CameraCfg( + height=128, + width=256, + offset=CameraCfg.OffsetCfg(pos=(0.0, 0.0, 4.0), rot=(0.0, 1.0, 0.0, 0.0), convention="ros"), + prim_path="/World/Camera", + update_period=0, + data_types=["rgb", "distance_to_camera"], + spawn=sim_utils.PinholeCameraCfg( + focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5) + ), + ) + sim_utils.create_new_stage() + dt = 0.01 + sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) + sim = sim_utils.SimulationContext(sim_cfg) + _populate_scene() + sim_utils.update_stage() + return sim, camera_cfg, dt + + +@pytest.fixture(scope="function") +def setup_camera_device(device): + """Fixture with explicit device parametrization for GPU/CPU testing.""" + sim, camera_cfg, dt = setup_with_device(device) + yield sim, camera_cfg, dt + teardown(sim) + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_multi_regex_init(setup_camera_device, device): + """Test multi-camera initialization with regex prim paths and content validation.""" + sim, camera_cfg, dt = setup_camera_device + + num_cameras = 9 + for i in range(num_cameras): + sim_utils.create_prim(f"/World/Origin_{i}", "Xform") + + camera_cfg = copy.deepcopy(camera_cfg) + camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" + camera = Camera(camera_cfg) + + sim.reset() + + assert camera.is_initialized + assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" + assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) + + assert camera.data.pos_w.shape == (num_cameras, 3) + assert camera.data.quat_w_ros.shape == (num_cameras, 4) + assert camera.data.quat_w_world.shape == (num_cameras, 4) + assert camera.data.quat_w_opengl.shape == (num_cameras, 4) + assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) + assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) + + for _ in range(10): + sim.step() + camera.update(dt) + for im_type, im_data in camera.data.output.items(): + if im_type == "rgb": + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) + for i in range(4): + assert (im_data[i] / 255.0).mean() > 0.0 + elif im_type == "distance_to_camera": + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) + for i in range(4): + assert im_data[i].mean() > 0.0 + del camera + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_all_annotators(setup_camera_device, device): + """Test all supported annotators produce correct shapes, dtypes, content, and info.""" + sim, camera_cfg, dt = setup_camera_device + all_annotator_types = [ + "rgb", + "rgba", + "albedo", + "depth", + "distance_to_camera", + "distance_to_image_plane", + "normals", + "motion_vectors", + "semantic_segmentation", + "instance_segmentation_fast", + "instance_id_segmentation_fast", + ] + + num_cameras = 9 + for i in range(num_cameras): + sim_utils.create_prim(f"/World/Origin_{i}", "Xform") + + camera_cfg = copy.deepcopy(camera_cfg) + camera_cfg.data_types = all_annotator_types + camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" + camera = Camera(camera_cfg) + + sim.reset() + + assert camera.is_initialized + assert sorted(camera.data.output.keys()) == sorted(all_annotator_types) + + for _ in range(10): + sim.step() + camera.update(dt) + for data_type, im_data in camera.data.output.items(): + if data_type in ["rgb", "normals"]: + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) + elif data_type in [ + "rgba", + "albedo", + "semantic_segmentation", + "instance_segmentation_fast", + "instance_id_segmentation_fast", + ]: + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) + for i in range(num_cameras): + assert (im_data[i] / 255.0).mean() > 0.0 + elif data_type in ["motion_vectors"]: + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) + for i in range(num_cameras): + assert im_data[i].mean() != 0.0 + elif data_type in ["depth", "distance_to_camera", "distance_to_image_plane"]: + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) + for i in range(num_cameras): + assert im_data[i].mean() > 0.0 + + output = camera.data.output + info = camera.data.info + assert output["rgb"].dtype == torch.uint8 + assert output["rgba"].dtype == torch.uint8 + assert output["albedo"].dtype == torch.uint8 + assert output["depth"].dtype == torch.float + assert output["distance_to_camera"].dtype == torch.float + assert output["distance_to_image_plane"].dtype == torch.float + assert output["normals"].dtype == torch.float + assert output["motion_vectors"].dtype == torch.float + assert output["semantic_segmentation"].dtype == torch.uint8 + assert output["instance_segmentation_fast"].dtype == torch.uint8 + assert output["instance_id_segmentation_fast"].dtype == torch.uint8 + assert isinstance(info[0]["semantic_segmentation"], dict) + assert isinstance(info[0]["instance_segmentation_fast"], dict) + assert isinstance(info[0]["instance_id_segmentation_fast"], dict) + + del camera + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_segmentation_non_colorize(setup_camera_device, device): + """Test segmentation outputs with colorization disabled produce correct dtypes and info.""" + sim, camera_cfg, dt = setup_camera_device + num_cameras = 9 + for i in range(num_cameras): + sim_utils.create_prim(f"/World/Origin_{i}", "Xform") + + 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 = Camera(camera_cfg) + + sim.reset() + + for _ in range(5): + sim.step() + camera.update(dt) + + for seg_type in camera_cfg.data_types: + assert camera.data.output[seg_type].shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) + assert camera.data.output[seg_type].dtype == torch.int32 + assert isinstance(camera.data.info[0][seg_type], dict) + + del camera + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_normals_unit_length(setup_camera_device, device): + """Test that normals output vectors have approximately unit length.""" + sim, camera_cfg, dt = setup_camera_device + num_cameras = 9 + for i in range(num_cameras): + sim_utils.create_prim(f"/World/Origin_{i}", "Xform") + + camera_cfg = copy.deepcopy(camera_cfg) + camera_cfg.data_types = ["normals"] + camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" + camera = Camera(camera_cfg) + + sim.reset() + + for _ in range(10): + sim.step() + camera.update(dt) + im_data = camera.data.output["normals"] + assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) + for i in range(4): + assert im_data[i].mean() > 0.0 + norms = torch.linalg.norm(im_data, dim=-1) + assert torch.allclose(norms, torch.ones_like(norms), atol=1e-9) + + assert camera.data.output["normals"].dtype == torch.float + del camera + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_data_types_ordering(setup_camera_device, device): + """Test that requesting specific data types produces the expected output keys.""" + sim, camera_cfg, dt = setup_camera_device + camera_cfg_distance = copy.deepcopy(camera_cfg) + camera_cfg_distance.data_types = ["distance_to_camera"] + camera_cfg_distance.prim_path = "/World/CameraDistance" + camera_distance = Camera(camera_cfg_distance) + + camera_cfg_depth = copy.deepcopy(camera_cfg) + camera_cfg_depth.data_types = ["depth"] + camera_cfg_depth.prim_path = "/World/CameraDepth" + camera_depth = Camera(camera_cfg_depth) + + camera_cfg_both = copy.deepcopy(camera_cfg) + camera_cfg_both.data_types = ["distance_to_camera", "depth"] + camera_cfg_both.prim_path = "/World/CameraBoth" + camera_both = Camera(camera_cfg_both) + + sim.reset() + + assert camera_distance.is_initialized + assert camera_depth.is_initialized + assert camera_both.is_initialized + assert list(camera_distance.data.output.keys()) == ["distance_to_camera"] + assert list(camera_depth.data.output.keys()) == ["depth"] + assert list(camera_both.data.output.keys()) == ["depth", "distance_to_camera"] + + del camera_distance + del camera_depth + del camera_both + + +@pytest.mark.parametrize("device", ["cuda:0"]) +@pytest.mark.isaacsim_ci +def test_camera_frame_offset(setup_camera_device, device): + """Test that camera reflects scene color changes without frame-offset lag.""" + sim, camera_cfg, dt = setup_camera_device + camera_cfg = copy.deepcopy(camera_cfg) + camera_cfg.height = 480 + camera_cfg.width = 480 + camera = Camera(camera_cfg) + + stage = sim_utils.get_current_stage() + for i in range(10): + prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") + color = Gf.Vec3f(1, 1, 1) + UsdGeom.Gprim(prim).GetDisplayColorAttr().Set([color]) + + sim.reset() + + for _ in range(100): + sim.step() + camera.update(dt) + + image_before = camera.data.output["rgb"].clone() / 255.0 + + for i in range(10): + prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") + color = Gf.Vec3f(0, 0, 0) + UsdGeom.Gprim(prim).GetDisplayColorAttr().Set([color]) + + sim.step() + camera.update(dt) + + image_after = camera.data.output["rgb"].clone() / 255.0 + + assert torch.abs(image_after - image_before).mean() > 0.01 + + del camera + + def _populate_scene(): """Add prims to the scene.""" # Ground-plane diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 6c90ce2696ca..247e3a4dc0ea 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -29,6 +29,10 @@ import isaaclab.sim as sim_utils from isaaclab.sensors.camera import TiledCamera, TiledCameraCfg +# Deprecation warnings from TiledCamera/TiledCameraCfg are expected in this file; +# the deprecation mechanism itself is validated in test_tiled_camera.py. +pytestmark = pytest.mark.filterwarnings("ignore::DeprecationWarning") + @pytest.fixture() def setup_camera(): @@ -241,9 +245,9 @@ def test_all_annotators_multi_tiled_camera(setup_camera): assert output["semantic_segmentation"].dtype == torch.uint8 assert output["instance_segmentation_fast"].dtype == torch.uint8 assert output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(info["semantic_segmentation"], dict) - assert isinstance(info["instance_segmentation_fast"], dict) - assert isinstance(info["instance_id_segmentation_fast"], dict) + assert isinstance(info[0]["semantic_segmentation"], dict) + assert isinstance(info[0]["instance_segmentation_fast"], dict) + assert isinstance(info[0]["instance_id_segmentation_fast"], dict) for camera in tiled_cameras: del camera diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 0fcf5f26c612..ad0f6d17851a 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -6,6 +6,14 @@ # ignore private usage of variables warning # pyright: reportPrivateUsage=none +"""Tests for the deprecated TiledCamera / TiledCameraCfg aliases. + +TiledCamera is now a thin subclass of Camera that emits a DeprecationWarning. +All substantive Camera tests live in ``test_camera.py``. This file only verifies +that the deprecation mechanism works correctly and that TiledCamera remains a +functional Camera alias. +""" + """Launch Isaac Sim Simulator first.""" from isaaclab.app import AppLauncher @@ -15,30 +23,27 @@ """Rest everything follows.""" -import copy import random +import warnings import numpy as np import pytest import torch -import warp as wp import omni.replicator.core as rep -from pxr import Gf, UsdGeom, UsdPhysics +from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils from isaaclab.sensors.camera import Camera, CameraCfg, TiledCamera, TiledCameraCfg -from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -from isaaclab.utils.timer import Timer @pytest.fixture(scope="function") -def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, float]: +def setup_camera(device) -> tuple[sim_utils.SimulationContext, CameraCfg, float]: """Fixture to set up and tear down the camera simulation environment.""" - camera_cfg = TiledCameraCfg( + camera_cfg = CameraCfg( height=128, width=256, - offset=TiledCameraCfg.OffsetCfg(pos=(0.0, 0.0, 4.0), rot=(0.0, 1.0, 0.0, 0.0), convention="ros"), + offset=CameraCfg.OffsetCfg(pos=(0.0, 0.0, 4.0), rot=(0.0, 1.0, 0.0, 0.0), convention="ros"), prim_path="/World/Camera", update_period=0, data_types=["rgb", "distance_to_camera"], @@ -66,189 +71,73 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.isaacsim_ci -def test_single_camera_init(setup_camera, device): - """Test single camera initialization.""" +def test_tiled_camera_deprecation_warning(setup_camera, device): + """TiledCamera instantiation emits a DeprecationWarning.""" sim, camera_cfg, dt = setup_camera - # Create camera - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[0].GetPath().pathString == camera_cfg.prim_path - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (1, 3) - assert camera.data.quat_w_ros.shape == (1, 4) - assert camera.data.quat_w_world.shape == (1, 4) - assert camera.data.quat_w_opengl.shape == (1, 4) - assert camera.data.intrinsic_matrices.shape == (1, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for im_type, im_data in camera.data.output.items(): - if im_type == "rgb": - assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 3) - assert (im_data / 255.0).mean() > 0.0 - elif im_type == "distance_to_camera": - assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 1) - assert im_data.mean() > 0.0 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_depth_clipping_max(setup_camera, device): - """Test depth max clipping.""" - sim, _, dt = setup_camera - # get camera cfgs - camera_cfg = TiledCameraCfg( - prim_path="/World/Camera", - offset=TiledCameraCfg.OffsetCfg(pos=(2.5, 2.5, 6.0), rot=(0.362, 0.873, -0.302, -0.125), convention="ros"), - spawn=sim_utils.PinholeCameraCfg().from_intrinsic_matrix( - focal_length=38.0, - intrinsic_matrix=[380.08, 0.0, 467.79, 0.0, 380.08, 262.05, 0.0, 0.0, 1.0], - height=540, - width=960, - clipping_range=(4.9, 5.0), - ), - height=540, - width=960, - data_types=["depth"], - depth_clipping_behavior="max", - ) - camera = TiledCamera(camera_cfg) - - # Play sim - sim.reset() - - camera.update(dt) - - assert len(camera.data.output["depth"][torch.isinf(camera.data.output["depth"])]) == 0 - assert camera.data.output["depth"].min() >= camera_cfg.spawn.clipping_range[0] - assert camera.data.output["depth"].max() <= camera_cfg.spawn.clipping_range[1] - + with warnings.catch_warnings(record=True) as w: + warnings.simplefilter("always") + camera = TiledCamera(camera_cfg) + deprecation_warnings = [x for x in w if issubclass(x.category, DeprecationWarning)] + assert len(deprecation_warnings) >= 1 + assert "TiledCamera is deprecated" in str(deprecation_warnings[0].message) del camera @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.isaacsim_ci -def test_depth_clipping_none(setup_camera, device): - """Test depth none clipping.""" - sim, _, dt = setup_camera - # get camera cfgs - camera_cfg = TiledCameraCfg( - prim_path="/World/Camera", - offset=TiledCameraCfg.OffsetCfg(pos=(2.5, 2.5, 6.0), rot=(0.362, 0.873, -0.302, -0.125), convention="ros"), - spawn=sim_utils.PinholeCameraCfg().from_intrinsic_matrix( - focal_length=38.0, - intrinsic_matrix=[380.08, 0.0, 467.79, 0.0, 380.08, 262.05, 0.0, 0.0, 1.0], - height=540, - width=960, - clipping_range=(4.9, 5.0), - ), - height=540, - width=960, - data_types=["depth"], - depth_clipping_behavior="none", - ) - camera = TiledCamera(camera_cfg) - - # Play sim - sim.reset() - - camera.update(dt) - - assert len(camera.data.output["depth"][torch.isinf(camera.data.output["depth"])]) > 0 - assert camera.data.output["depth"].min() >= camera_cfg.spawn.clipping_range[0] - if len(camera.data.output["depth"][~torch.isinf(camera.data.output["depth"])]) > 0: - assert ( - camera.data.output["depth"][~torch.isinf(camera.data.output["depth"])].max() - <= camera_cfg.spawn.clipping_range[1] +def test_tiled_camera_cfg_deprecation_warning(setup_camera, device): + """TiledCameraCfg instantiation emits a DeprecationWarning.""" + with warnings.catch_warnings(record=True) as w: + warnings.simplefilter("always") + cfg = TiledCameraCfg( + height=128, + width=256, + prim_path="/World/Camera", + data_types=["rgb"], + spawn=sim_utils.PinholeCameraCfg( + focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5) + ), ) - - del camera + deprecation_warnings = [x for x in w if issubclass(x.category, DeprecationWarning)] + assert len(deprecation_warnings) >= 1 + assert "TiledCameraCfg is deprecated" in str(deprecation_warnings[0].message) +@pytest.mark.filterwarnings("ignore::DeprecationWarning") @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.isaacsim_ci -def test_depth_clipping_zero(setup_camera, device): - """Test depth zero clipping.""" - sim, _, dt = setup_camera - # get camera cfgs - camera_cfg = TiledCameraCfg( - prim_path="/World/Camera", - offset=TiledCameraCfg.OffsetCfg(pos=(2.5, 2.5, 6.0), rot=(0.362, 0.873, -0.302, -0.125), convention="ros"), - spawn=sim_utils.PinholeCameraCfg().from_intrinsic_matrix( - focal_length=38.0, - intrinsic_matrix=[380.08, 0.0, 467.79, 0.0, 380.08, 262.05, 0.0, 0.0, 1.0], - height=540, - width=960, - clipping_range=(4.9, 5.0), - ), - height=540, - width=960, - data_types=["depth"], - depth_clipping_behavior="zero", - ) +def test_tiled_camera_is_camera_subclass(setup_camera, device): + """TiledCamera is a subclass of Camera, so isinstance checks work.""" + sim, camera_cfg, dt = setup_camera camera = TiledCamera(camera_cfg) - - # Play sim - sim.reset() - - camera.update(dt) - - assert len(camera.data.output["depth"][torch.isinf(camera.data.output["depth"])]) == 0 - assert camera.data.output["depth"].min() == 0.0 - assert camera.data.output["depth"].max() <= camera_cfg.spawn.clipping_range[1] - + assert isinstance(camera, Camera) + assert isinstance(camera, TiledCamera) del camera +@pytest.mark.filterwarnings("ignore::DeprecationWarning") @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.isaacsim_ci -def test_multi_camera_init(setup_camera, device): - """Test multi-camera initialization.""" +def test_tiled_camera_basic_functionality(setup_camera, device): + """TiledCamera produces correct output (proving it delegates to Camera).""" sim, camera_cfg, dt = setup_camera - - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized assert camera.is_initialized # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" + assert camera._sensor_prims[0].GetPath().pathString == camera_cfg.prim_path assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) + assert camera.data.pos_w.shape == (1, 3) + assert camera.data.intrinsic_matrices.shape == (1, 3, 3) assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) # Simulate physics - for _ in range(10): + for _ in range(5): # perform rendering sim.step() # update camera @@ -256,1477 +145,19 @@ def test_multi_camera_init(setup_camera, device): # check image data for im_type, im_data in camera.data.output.items(): if im_type == "rgb": - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 + assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 3) + assert (im_data / 255.0).mean() > 0.0 elif im_type == "distance_to_camera": - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(4): - assert im_data[i].mean() > 0.0 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_rgb_only_camera(setup_camera, device): - """Test initialization with only RGB data type.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["rgb"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["rgba", "rgb"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - im_data = camera.data.output["rgb"] - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["rgb"].dtype == torch.uint8 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_data_types(setup_camera, device): - """Test different data types for camera initialization.""" - sim, camera_cfg, dt = setup_camera - # Create camera - camera_cfg_distance = copy.deepcopy(camera_cfg) - camera_cfg_distance.data_types = ["distance_to_camera"] - camera_cfg_distance.prim_path = "/World/CameraDistance" - camera_distance = TiledCamera(camera_cfg_distance) - camera_cfg_depth = copy.deepcopy(camera_cfg) - camera_cfg_depth.data_types = ["depth"] - camera_cfg_depth.prim_path = "/World/CameraDepth" - camera_depth = TiledCamera(camera_cfg_depth) - camera_cfg_both = copy.deepcopy(camera_cfg) - camera_cfg_both.data_types = ["distance_to_camera", "depth"] - camera_cfg_both.prim_path = "/World/CameraBoth" - camera_both = TiledCamera(camera_cfg_both) - - # Play sim - sim.reset() - - # Check if cameras are initialized - assert camera_distance.is_initialized - assert camera_depth.is_initialized - assert camera_both.is_initialized - - # Check if camera prims are set correctly and that they are camera prims - assert camera_distance._sensor_prims[0].GetPath().pathString == "/World/CameraDistance" - assert isinstance(camera_distance._sensor_prims[0], UsdGeom.Camera) - assert camera_depth._sensor_prims[0].GetPath().pathString == "/World/CameraDepth" - assert isinstance(camera_depth._sensor_prims[0], UsdGeom.Camera) - assert camera_both._sensor_prims[0].GetPath().pathString == "/World/CameraBoth" - assert isinstance(camera_both._sensor_prims[0], UsdGeom.Camera) - assert list(camera_distance.data.output.keys()) == ["distance_to_camera"] - assert list(camera_depth.data.output.keys()) == ["depth"] - assert list(camera_both.data.output.keys()) == ["depth", "distance_to_camera"] - - del camera_distance - del camera_depth - del camera_both - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_depth_only_camera(setup_camera, device): - """Test initialization with only depth.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["distance_to_camera"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["distance_to_camera"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - im_data = camera.data.output["distance_to_camera"] - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(4): - assert im_data[i].mean() > 0.0 - assert camera.data.output["distance_to_camera"].dtype == torch.float - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_rgba_only_camera(setup_camera, device): - """Test initialization with only RGBA.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["rgba"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["rgba"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["rgba"].dtype == torch.uint8 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_albedo_only_camera(setup_camera, device): - """Test initialization with only albedo.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["albedo"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["albedo"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["albedo"].dtype == torch.uint8 - del camera - - -@pytest.mark.parametrize( - "data_type", - ["simple_shading_constant_diffuse", "simple_shading_diffuse_mdl", "simple_shading_full_mdl"], -) -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_simple_shading_only_camera(setup_camera, device, data_type): - """Test initialization with only simple shading.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = [data_type] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == [data_type] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output[data_type].dtype == torch.uint8 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_distance_to_camera_only_camera(setup_camera, device): - """Test initialization with only distance_to_camera.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["distance_to_camera"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["distance_to_camera"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(4): - assert im_data[i].mean() > 0.0 - assert camera.data.output["distance_to_camera"].dtype == torch.float + assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 1) + assert im_data.mean() > 0.0 del camera -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_distance_to_image_plane_only_camera(setup_camera, device): - """Test initialization with only distance_to_image_plane.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["distance_to_image_plane"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["distance_to_image_plane"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(4): - assert im_data[i].mean() > 0.0 - assert camera.data.output["distance_to_image_plane"].dtype == torch.float - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_normals_only_camera(setup_camera, device): - """Test initialization with only normals.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["normals"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["normals"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - for i in range(4): - assert im_data[i].mean() > 0.0 - # check normal norm is approximately 1 - norms = torch.linalg.norm(im_data, dim=-1) - assert torch.allclose(norms, torch.ones_like(norms), atol=1e-9) - assert camera.data.output["normals"].dtype == torch.float - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_motion_vectors_only_camera(setup_camera, device): - """Test initialization with only motion_vectors.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["motion_vectors"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["motion_vectors"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) - for i in range(4): - assert im_data[i].mean() != 0.0 - assert camera.data.output["motion_vectors"].dtype == torch.float - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_semantic_segmentation_colorize_only_camera(setup_camera, device): - """Test initialization with only semantic_segmentation.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["semantic_segmentation"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["semantic_segmentation"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(4): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["semantic_segmentation"].dtype == torch.uint8 - assert isinstance(camera.data.info["semantic_segmentation"], dict) - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_instance_segmentation_fast_colorize_only_camera(setup_camera, device): - """Test initialization with only instance_segmentation_fast.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["instance_segmentation_fast"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["instance_segmentation_fast"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["instance_segmentation_fast"].dtype == torch.uint8 - assert isinstance(camera.data.info["instance_segmentation_fast"], dict) - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_instance_id_segmentation_fast_colorize_only_camera(setup_camera, device): - """Test initialization with only instance_id_segmentation_fast.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["instance_id_segmentation_fast"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["instance_id_segmentation_fast"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.0 - assert camera.data.output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(camera.data.info["instance_id_segmentation_fast"], dict) - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_semantic_segmentation_non_colorize_only_camera(setup_camera, device): - """Test initialization with only semantic_segmentation.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["semantic_segmentation"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera_cfg.colorize_semantic_segmentation = False - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["semantic_segmentation"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].to(dtype=float).mean() > 0.0 - assert camera.data.output["semantic_segmentation"].dtype == torch.int32 - assert isinstance(camera.data.info["semantic_segmentation"], dict) - - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_instance_segmentation_fast_non_colorize_only_camera(setup_camera, device): - """Test initialization with only instance_segmentation_fast.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["instance_segmentation_fast"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera_cfg.colorize_instance_segmentation = False - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["instance_segmentation_fast"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].to(dtype=float).mean() > 0.0 - assert camera.data.output["instance_segmentation_fast"].dtype == torch.int32 - assert isinstance(camera.data.info["instance_segmentation_fast"], dict) - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -def test_instance_id_segmentation_fast_non_colorize_only_camera(setup_camera, device): - """Test initialization with only instance_id_segmentation_fast.""" - sim, camera_cfg, dt = setup_camera - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = ["instance_id_segmentation_fast"] - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera_cfg.colorize_instance_id_segmentation = False - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert list(camera.data.output.keys()) == ["instance_id_segmentation_fast"] - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for _, im_data in camera.data.output.items(): - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].to(dtype=float).mean() > 0.0 - assert camera.data.output["instance_id_segmentation_fast"].dtype == torch.int32 - assert isinstance(camera.data.info["instance_id_segmentation_fast"], dict) - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_all_annotators_camera(setup_camera, device): - """Test initialization with all supported annotators.""" - sim, camera_cfg, dt = setup_camera - all_annotator_types = [ - "rgb", - "rgba", - "albedo", - "depth", - "distance_to_camera", - "distance_to_image_plane", - "normals", - "motion_vectors", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ] - - num_cameras = 9 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = all_annotator_types - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert sorted(camera.data.output.keys()) == sorted(all_annotator_types) - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for data_type, im_data in camera.data.output.items(): - if data_type in ["rgb", "normals"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - elif data_type in [ - "rgba", - "albedo", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.0 - elif data_type in ["motion_vectors"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) - for i in range(num_cameras): - assert im_data[i].mean() != 0.0 - elif data_type in ["depth", "distance_to_camera", "distance_to_image_plane"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].mean() > 0.0 - - # access image data and compare dtype - output = camera.data.output - info = camera.data.info - assert output["rgb"].dtype == torch.uint8 - assert output["rgba"].dtype == torch.uint8 - assert output["albedo"].dtype == torch.uint8 - assert output["depth"].dtype == torch.float - assert output["distance_to_camera"].dtype == torch.float - assert output["distance_to_image_plane"].dtype == torch.float - assert output["normals"].dtype == torch.float - assert output["motion_vectors"].dtype == torch.float - assert output["semantic_segmentation"].dtype == torch.uint8 - assert output["instance_segmentation_fast"].dtype == torch.uint8 - assert output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(info["semantic_segmentation"], dict) - assert isinstance(info["instance_segmentation_fast"], dict) - assert isinstance(info["instance_id_segmentation_fast"], dict) - - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_all_annotators_low_resolution_camera(setup_camera, device): - """Test initialization with all supported annotators.""" - sim, camera_cfg, dt = setup_camera - all_annotator_types = [ - "rgb", - "rgba", - "albedo", - "depth", - "distance_to_camera", - "distance_to_image_plane", - "normals", - "motion_vectors", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ] - - num_cameras = 2 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.height = 40 - camera_cfg.width = 40 - camera_cfg.data_types = all_annotator_types - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert sorted(camera.data.output.keys()) == sorted(all_annotator_types) - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for data_type, im_data in camera.data.output.items(): - if data_type in ["rgb", "normals"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - elif data_type in [ - "rgba", - "albedo", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.0 - elif data_type in ["motion_vectors"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) - for i in range(num_cameras): - assert im_data[i].mean() != 0.0 - elif data_type in ["depth", "distance_to_camera", "distance_to_image_plane"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].mean() > 0.0 - - # access image data and compare dtype - output = camera.data.output - info = camera.data.info - assert output["rgb"].dtype == torch.uint8 - assert output["rgba"].dtype == torch.uint8 - assert output["albedo"].dtype == torch.uint8 - assert output["depth"].dtype == torch.float - assert output["distance_to_camera"].dtype == torch.float - assert output["distance_to_image_plane"].dtype == torch.float - assert output["normals"].dtype == torch.float - assert output["motion_vectors"].dtype == torch.float - assert output["semantic_segmentation"].dtype == torch.uint8 - assert output["instance_segmentation_fast"].dtype == torch.uint8 - assert output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(info["semantic_segmentation"], dict) - assert isinstance(info["instance_segmentation_fast"], dict) - assert isinstance(info["instance_id_segmentation_fast"], dict) - - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_all_annotators_non_perfect_square_number_camera(setup_camera, device): - """Test initialization with all supported annotators.""" - sim, camera_cfg, dt = setup_camera - all_annotator_types = [ - "rgb", - "rgba", - "albedo", - "depth", - "distance_to_camera", - "distance_to_image_plane", - "normals", - "motion_vectors", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ] - - num_cameras = 11 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform") - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.data_types = all_annotator_types - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert sorted(camera.data.output.keys()) == sorted(all_annotator_types) - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Simulate physics - for _ in range(10): - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for data_type, im_data in camera.data.output.items(): - if data_type in ["rgb", "normals"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - elif data_type in [ - "rgba", - "albedo", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.0 - elif data_type in ["motion_vectors"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) - for i in range(num_cameras): - assert im_data[i].mean() != 0.0 - elif data_type in ["depth", "distance_to_camera", "distance_to_image_plane"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].mean() > 0.0 - - # access image data and compare dtype - output = camera.data.output - info = camera.data.info - assert output["rgb"].dtype == torch.uint8 - assert output["rgba"].dtype == torch.uint8 - assert output["albedo"].dtype == torch.uint8 - assert output["depth"].dtype == torch.float - assert output["distance_to_camera"].dtype == torch.float - assert output["distance_to_image_plane"].dtype == torch.float - assert output["normals"].dtype == torch.float - assert output["motion_vectors"].dtype == torch.float - assert output["semantic_segmentation"].dtype == torch.uint8 - assert output["instance_segmentation_fast"].dtype == torch.uint8 - assert output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(info["semantic_segmentation"], dict) - assert isinstance(info["instance_segmentation_fast"], dict) - assert isinstance(info["instance_id_segmentation_fast"], dict) - - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_all_annotators_instanceable(setup_camera, device): - """Test initialization with all supported annotators on instanceable assets.""" - sim, camera_cfg, dt = setup_camera - all_annotator_types = [ - "rgb", - "rgba", - "albedo", - "depth", - "distance_to_camera", - "distance_to_image_plane", - "normals", - "motion_vectors", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ] - - num_cameras = 10 - for i in range(num_cameras): - sim_utils.create_prim(f"/World/Origin_{i}", "Xform", translation=(0.0, i, 0.0)) - - # Create a stage with 10 instanceable cubes, where each camera points to one cube - stage = sim_utils.get_current_stage() - for i in range(10): - # Remove objects added to stage by default - stage.RemovePrim(f"/World/Objects/Obj_{i:02d}") - # Add instanceable cubes - sim_utils.create_prim( - f"/World/Cube_{i}", - "Xform", - usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - translation=(0.0, i, 5.0), - orientation=(0.0, 0.0, 0.0, 1.0), - scale=(1.0, 1.0, 1.0), - ) - prim = stage.GetPrimAtPath(f"/World/Cube_{i}") - sim_utils.add_labels(prim, labels=["cube"], instance_name="class") - - # Disable gravity — we teleport cubes explicitly to get deterministic motion vectors - physics_scene = UsdPhysics.Scene(stage.GetPrimAtPath(sim.cfg.physics_prim_path)) - physics_scene.GetGravityMagnitudeAttr().Set(0.0) - - # Create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.height = 120 - camera_cfg.width = 80 - camera_cfg.data_types = all_annotator_types - camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" - camera_cfg.offset.pos = (0.0, 0.0, 5.5) - camera = TiledCamera(camera_cfg) - # Check simulation parameter is set correctly - assert sim.get_setting("/isaaclab/render/rtx_sensors") - # Play sim - sim.reset() - # Check if camera is initialized - assert camera.is_initialized - # Check if camera prim is set correctly and that it is a camera prim - assert camera._sensor_prims[1].GetPath().pathString == "/World/Origin_1/CameraSensor" - assert isinstance(camera._sensor_prims[0], UsdGeom.Camera) - assert sorted(camera.data.output.keys()) == sorted(all_annotator_types) - - # Check buffers that exists and have correct shapes - assert camera.data.pos_w.shape == (num_cameras, 3) - assert camera.data.quat_w_ros.shape == (num_cameras, 4) - assert camera.data.quat_w_world.shape == (num_cameras, 4) - assert camera.data.quat_w_opengl.shape == (num_cameras, 4) - assert camera.data.intrinsic_matrices.shape == (num_cameras, 3, 3) - assert camera.data.image_shape == (camera_cfg.height, camera_cfg.width) - - # Create a rigid body view so we can teleport the cubes each frame - physics_sim_view = sim.physics_manager.get_physics_sim_view() - cube_view = physics_sim_view.create_rigid_body_view("/World/Cube_*") - all_indices = torch.arange(num_cameras, dtype=torch.int32, device=device) - - for frame in range(2): - # Build transforms: [x, y, z, qx, qy, qz, qw] — move cubes down by 0.5 each frame - transforms = torch.zeros(num_cameras, 7, device=device) - for i in range(num_cameras): - transforms[i, 0] = 0.0 # x - transforms[i, 1] = float(i) # y - transforms[i, 2] = 5.0 - frame * 0.5 # z — moves down 0.5 per frame - transforms[i, 6] = 1.0 # qw (identity orientation, xyzw format) - cube_view.set_transforms(wp.from_torch(transforms), wp.from_torch(all_indices)) - # Zero out velocities so physics doesn't fight the teleport - cube_view.set_velocities(wp.from_torch(torch.zeros(num_cameras, 6, device=device)), wp.from_torch(all_indices)) - sim.step() - - # Teleport cubes to explicit positions each frame so motion vectors are deterministic - for frame in range(3): - # Build transforms: [x, y, z, qx, qy, qz, qw] — move cubes down by 0.5 each frame - transforms = torch.zeros(num_cameras, 7, device=device) - for i in range(num_cameras): - transforms[i, 0] = 0.0 # x - transforms[i, 1] = float(i) # y - transforms[i, 2] = 5.0 - frame * 0.5 # z — moves down 0.5 per frame - transforms[i, 6] = 1.0 # qw (identity orientation, xyzw format) - cube_view.set_transforms(wp.from_torch(transforms), wp.from_torch(all_indices)) - # Zero out velocities so physics doesn't fight the teleport - cube_view.set_velocities(wp.from_torch(torch.zeros(num_cameras, 6, device=device)), wp.from_torch(all_indices)) - - # perform rendering - sim.step() - # update camera - camera.update(dt) - # check image data - for data_type, im_data in camera.data.output.items(): - if data_type in ["rgb", "normals"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 3) - elif data_type in [ - "rgba", - "albedo", - "semantic_segmentation", - "instance_segmentation_fast", - "instance_id_segmentation_fast", - ]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 4) - for i in range(num_cameras): - assert (im_data[i] / 255.0).mean() > 0.2 - elif data_type in ["motion_vectors"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 2) - for i in range(num_cameras): - # TODO: this looks broken on tot - # assert im_data[i].abs().mean() > 0.001 - print(im_data[i].abs().mean()) - elif data_type in ["depth", "distance_to_camera", "distance_to_image_plane"]: - assert im_data.shape == (num_cameras, camera_cfg.height, camera_cfg.width, 1) - for i in range(num_cameras): - assert im_data[i].mean() > 2.0 - - # access image data and compare dtype - output = camera.data.output - info = camera.data.info - assert output["rgb"].dtype == torch.uint8 - assert output["rgba"].dtype == torch.uint8 - assert output["albedo"].dtype == torch.uint8 - assert output["depth"].dtype == torch.float - assert output["distance_to_camera"].dtype == torch.float - assert output["distance_to_image_plane"].dtype == torch.float - assert output["normals"].dtype == torch.float - assert output["motion_vectors"].dtype == torch.float - assert output["semantic_segmentation"].dtype == torch.uint8 - assert output["instance_segmentation_fast"].dtype == torch.uint8 - assert output["instance_id_segmentation_fast"].dtype == torch.uint8 - assert isinstance(info["semantic_segmentation"], dict) - assert isinstance(info["instance_segmentation_fast"], dict) - assert isinstance(info["instance_id_segmentation_fast"], dict) - - del camera - - -@pytest.mark.parametrize("device", ["cuda:0"]) -@pytest.mark.isaacsim_ci -def test_throughput(setup_camera, device): - """Test tiled camera throughput.""" - sim, camera_cfg, dt = setup_camera - # create camera - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.height = 480 - camera_cfg.width = 640 - camera = TiledCamera(camera_cfg) - - # Play simulator - sim.reset() - - # Simulate physics - for _ in range(5): - # perform rendering - sim.step() - # update camera - with Timer(f"Time taken for updating camera with shape {camera.image_shape}"): - camera.update(dt) - # Check image data - for im_type, im_data in camera.data.output.items(): - if im_type == "rgb": - assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 3) - assert (im_data / 255.0).mean() > 0.0 - elif im_type == "distance_to_camera": - assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 1) - assert im_data.mean() > 0.0 - del camera - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_output_equal_to_usd_camera_intrinsics(setup_camera, device): - """ - Test that the output of the ray caster camera and the usd camera are the same when both are - initialized with the same intrinsic matrix. - """ - sim, _, dt = setup_camera - # create cameras - offset_rot = (-0.1251, 0.3617, 0.8731, -0.3020) - offset_pos = (2.5, 2.5, 4.0) - intrinsics = [380.08, 0.0, 467.79, 0.0, 380.08, 262.05, 0.0, 0.0, 1.0] - # get camera cfgs - # TODO: add clipping range back, once correctly supported by tiled camera - camera_tiled_cfg = TiledCameraCfg( - prim_path="/World/Camera_tiled", - offset=TiledCameraCfg.OffsetCfg(pos=offset_pos, rot=offset_rot, convention="ros"), - spawn=sim_utils.PinholeCameraCfg.from_intrinsic_matrix( - intrinsic_matrix=intrinsics, - height=540, - width=960, - ), - height=540, - width=960, - data_types=["depth"], - ) - camera_usd_cfg = CameraCfg( - prim_path="/World/Camera_usd", - offset=CameraCfg.OffsetCfg(pos=offset_pos, rot=offset_rot, convention="ros"), - spawn=sim_utils.PinholeCameraCfg.from_intrinsic_matrix( - intrinsic_matrix=intrinsics, - height=540, - width=960, - ), - height=540, - width=960, - data_types=["distance_to_image_plane"], - ) - - # set aperture offsets to 0, as currently not supported for usd/ tiled camera - camera_tiled_cfg.spawn.horizontal_aperture_offset = 0 - camera_tiled_cfg.spawn.vertical_aperture_offset = 0 - camera_usd_cfg.spawn.horizontal_aperture_offset = 0 - camera_usd_cfg.spawn.vertical_aperture_offset = 0 - # init cameras - camera_tiled = TiledCamera(camera_tiled_cfg) - camera_usd = Camera(camera_usd_cfg) - - # play sim - sim.reset() - sim.play() - - # perform steps - for _ in range(5): - sim.step() - - # update camera - camera_usd.update(dt) - camera_tiled.update(dt) - - # filter nan and inf from output - cam_tiled_output = camera_tiled.data.output["depth"].clone() - cam_usd_output = camera_usd.data.output["distance_to_image_plane"].clone() - cam_tiled_output[torch.isnan(cam_tiled_output)] = 0 - cam_tiled_output[torch.isinf(cam_tiled_output)] = 0 - cam_usd_output[torch.isnan(cam_usd_output)] = 0 - cam_usd_output[torch.isinf(cam_usd_output)] = 0 - - # check that both have the same intrinsic matrices - torch.testing.assert_close(camera_tiled.data.intrinsic_matrices[0], camera_usd.data.intrinsic_matrices[0]) - - # check the apertures - torch.testing.assert_close( - camera_usd._sensor_prims[0].GetHorizontalApertureAttr().Get(), - camera_tiled._sensor_prims[0].GetHorizontalApertureAttr().Get(), - ) - torch.testing.assert_close( - camera_usd._sensor_prims[0].GetVerticalApertureAttr().Get(), - camera_tiled._sensor_prims[0].GetVerticalApertureAttr().Get(), - ) - - # check image data - torch.testing.assert_close( - cam_tiled_output[..., 0], - cam_usd_output[..., 0], - atol=5e-5, - rtol=5e-6, - ) - - del camera_tiled - del camera_usd - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci -def test_sensor_print(setup_camera, device): - """Test sensor print is working correctly.""" - sim, camera_cfg, _ = setup_camera - # Create sensor - sensor = TiledCamera(cfg=camera_cfg) - # Play sim - sim.reset() - # print info - print(sensor) - - -@pytest.mark.parametrize("device", ["cuda:0"]) -@pytest.mark.isaacsim_ci -def test_frame_offset_small_resolution(setup_camera, device): - """Test frame offset issue with small resolution camera.""" - sim, camera_cfg, dt = setup_camera - # Create sensor - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.height = 80 - camera_cfg.width = 80 - # Objects are scaled to (1,1,1): USD default cube is 2×2×2, so half-height=1.0, - # settled objects rest at z=1.0 (center) with top at z=2.0. Place the camera - # above the objects so they are fully visible from above. - camera_cfg.offset.pos = (0.0, 0.0, 3.0) - tiled_camera = TiledCamera(camera_cfg) - # play sim - sim.reset() - # simulate some steps first to make sure objects are settled - stage = sim_utils.get_current_stage() - for i in range(10): - prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") - UsdGeom.Gprim(prim).GetOrderedXformOps()[2].Set(Gf.Vec3d(1.0, 1.0, 1.0)) - for i in range(100): - # step simulation - sim.step() - # update camera - tiled_camera.update(dt) - # collect image data - image_before = tiled_camera.data.output["rgb"].clone() / 255.0 - - # update scene - for i in range(10): - prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") - color = Gf.Vec3f(0.0, 0.0, 0.0) - UsdGeom.Gprim(prim).GetDisplayColorAttr().Set([color]) - - # update rendering (step 1 – replicator annotator has a one-frame offset, - # so the colour change may not be reflected yet) - sim.step() - tiled_camera.update(dt) - - # make sure the image is different - image_after = tiled_camera.data.output["rgb"].clone() / 255.0 - - # check difference is above threshold - assert torch.abs(image_after - image_before).mean() > 0.02 # images of same color should be below 0.01 - - -@pytest.mark.parametrize("device", ["cuda:0"]) -@pytest.mark.isaacsim_ci -def test_frame_offset_large_resolution(setup_camera, device): - """Test frame offset issue with large resolution camera.""" - sim, camera_cfg, dt = setup_camera - # Create sensor - camera_cfg = copy.deepcopy(camera_cfg) - camera_cfg.height = 480 - camera_cfg.width = 480 - tiled_camera = TiledCamera(camera_cfg) - - # modify scene to be less stochastic - stage = sim_utils.get_current_stage() - for i in range(10): - prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") - color = Gf.Vec3f(1, 1, 1) - UsdGeom.Gprim(prim).GetDisplayColorAttr().Set([color]) - - # play sim - sim.reset() - # simulate some steps first to make sure objects are settled - for i in range(100): - # step simulation - sim.step() - # update camera - tiled_camera.update(dt) - # collect image data - image_before = tiled_camera.data.output["rgb"].clone() / 255.0 - - # update scene - for i in range(10): - prim = stage.GetPrimAtPath(f"/World/Objects/Obj_{i:02d}") - color = Gf.Vec3f(0, 0, 0) - UsdGeom.Gprim(prim).GetDisplayColorAttr().Set([color]) - - # update rendering - sim.step() - tiled_camera.update(dt) - - # make sure the image is different - image_after = tiled_camera.data.output["rgb"].clone() / 255.0 - - # check difference is above threshold - assert torch.abs(image_after - image_before).mean() > 0.01 # images of same color should be below 0.001 - - """ Helper functions. """ -@staticmethod def _populate_scene(): """Add prims to the scene.""" # Ground-plane From aa0e5a8e4858c6bc992f003a17b1671465dd352a Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 2 Apr 2026 20:48:34 -0700 Subject: [PATCH 3/4] Bump extension version and update CHANGELOG.md --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 31 +++++++++++++++++++++++++++ 2 files changed, 32 insertions(+), 1 deletion(-) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 52f92be2364e..24d3151cda98 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.5.25" +version = "4.5.26" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 5269d6946b01..270ecda0320b 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,37 @@ Changelog --------- +4.5.26 (2026-04-02) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Unified :class:`~isaaclab.sensors.camera.Camera` and :class:`~isaaclab.sensors.camera.TiledCamera` + into a single implementation. :class:`Camera` now delegates all rendering to the + :class:`~isaaclab.renderers.Renderer` abstraction (same approach :class:`TiledCamera` used). + The public API is unchanged for :class:`Camera` users. +* **Breaking (TiledCamera users):** :attr:`~isaaclab.sensors.camera.CameraData.info` now correctly + returns ``list[dict[str, Any]]`` (per-camera, then per-data-type) as documented in + :class:`~isaaclab.sensors.camera.CameraData`. :class:`TiledCamera` previously returned a flat + ``dict``, which violated the documented contract. Migration: replace + ``camera.data.info[data_type]`` with ``camera.data.info[cam_idx][data_type]``. + +Deprecated +^^^^^^^^^^ + +* :class:`~isaaclab.sensors.camera.TiledCamera` is deprecated. Use + :class:`~isaaclab.sensors.camera.Camera` directly — it now supports all renderer backends. +* :class:`~isaaclab.sensors.camera.TiledCameraCfg` is deprecated. Use + :class:`~isaaclab.sensors.camera.CameraCfg` directly. + +Removed +^^^^^^^ + +* Removed :attr:`~isaaclab.sensors.camera.Camera.render_product_paths`. Render products are + now managed internally by the renderer backend and are not part of the public API. + + 4.5.25 (2026-04-01) ~~~~~~~~~~~~~~~~~~~ From db7e5712f7e199c8cc2da28cb640f51cf52bfa53 Mon Sep 17 00:00:00 2001 From: nvsekkin Date: Thu, 2 Apr 2026 20:57:20 -0700 Subject: [PATCH 4/4] Formatting and contributor --- CONTRIBUTORS.md | 1 + source/isaaclab/test/sensors/test_tiled_camera.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 318e1106c688..829d6d7df3e1 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -71,6 +71,7 @@ Guidelines for modifications: * Dhananjay Shendre * Dongxuan Fan * Dorsa Rohani +* Ege Sekkin * Emily Sturman * Emmanuel Ferdman * Fabian Jenelten diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index ad0f6d17851a..4ce62cd5336f 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -89,7 +89,7 @@ def test_tiled_camera_cfg_deprecation_warning(setup_camera, device): """TiledCameraCfg instantiation emits a DeprecationWarning.""" with warnings.catch_warnings(record=True) as w: warnings.simplefilter("always") - cfg = TiledCameraCfg( + _cfg = TiledCameraCfg( height=128, width=256, prim_path="/World/Camera",