diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera.py index 5f57b8bbb6..2b47aa33e9 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera.py @@ -501,7 +501,7 @@ def _update_buffers_impl(self, env_ids: Sequence[int]): # apply defined clipping behavior if ( name == "distance_to_camera" or name == "distance_to_image_plane" - ) and self.cfg.depth_clipping_behavior is not None: + ) 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] ) @@ -630,7 +630,7 @@ def _create_annotator_data(self): # clip the data if needed if ( name == "distance_to_camera" or name == "distance_to_image_plane" - ) and self.cfg.depth_clipping_behavior is not None: + ) 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] ) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera_cfg.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera_cfg.py index 67e2635706..18052d4d16 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera_cfg.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/camera_cfg.py @@ -53,12 +53,12 @@ class OffsetCfg: asset is already present in the scene. """ - depth_clipping_behavior: Literal["max", "zero"] | None = "zero" + depth_clipping_behavior: Literal["max", "zero", "none"] = "zero" """Clipping behavior for the camera for values exceed the maximum value. Defaults to "zero". - ``"max"``: Values are clipped to the maximum value. - ``"zero"``: Values are clipped to zero. - - ``None``: No clipping is applied. Values will be returned as ``inf``. + - ``"none``: No clipping is applied. Values will be returned as ``inf``. """ data_types: list[str] = ["rgb"] diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera.py index 7fcb3922e1..66493d3060 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera.py @@ -44,6 +44,10 @@ class TiledCamera(Camera): tiled rendering process. Various ray tracing effects such as reflections, refractions, and shadows may not be accurately captured in the RGB images. We are currently working on improving the fidelity of the RGB images. + .. note:: + Compared to other cameras, the depth clipping behavior cannot be altered as the backend implementation + automatically clips the values exceeding the maximum range to zero. + .. versionadded:: v1.0.0 This feature is available starting from Isaac Sim 4.0. Before this version, the tiled rendering APIs diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera_cfg.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera_cfg.py index 384709a5a8..45ffaa0019 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera_cfg.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/camera/tiled_camera_cfg.py @@ -15,13 +15,7 @@ @configclass class TiledCameraCfg(SensorBaseCfg): - """Configuration for a tiled rendering-based camera sensor. - - .. note:: - - Compared to other cameras, the clipping behavior cannot be altered as the backend implementation automatically - clips the values exceeding the maximum range to zero. - """ + """Configuration for a tiled rendering-based camera sensor.""" @configclass class OffsetCfg: diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/ray_caster/ray_caster_camera_cfg.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/ray_caster/ray_caster_camera_cfg.py index 3f9631d154..bbe0eb3b9d 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/ray_caster/ray_caster_camera_cfg.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/sensors/ray_caster/ray_caster_camera_cfg.py @@ -44,12 +44,12 @@ class OffsetCfg: data_types: list[str] = ["distance_to_image_plane"] """List of sensor names/types to enable for the camera. Defaults to ["distance_to_image_plane"].""" - depth_clipping_behavior: Literal["max", "zero"] | None = "zero" + depth_clipping_behavior: Literal["max", "zero", "none"] = "zero" """Clipping behavior for the camera for values exceed the maximum value. Defaults to "zero". - ``"max"``: Values are clipped to the maximum value. - ``"zero"``: Values are clipped to zero. - - ``None``: No clipping is applied. Values will be returned as ``nan``. + - ``"none``: No clipping is applied. Values will be returned as ``nan``. """ def __post_init__(self): diff --git a/source/extensions/omni.isaac.lab/test/sensors/test_camera.py b/source/extensions/omni.isaac.lab/test/sensors/test_camera.py index b9786c6534..42274145f2 100644 --- a/source/extensions/omni.isaac.lab/test/sensors/test_camera.py +++ b/source/extensions/omni.isaac.lab/test/sensors/test_camera.py @@ -368,8 +368,8 @@ def test_depth_clipping(self): This test is the same for all camera models to enforce the same clipping behavior. """ # get camera cfgs - camera_cfg = CameraCfg( - prim_path="/World/Camera", + camera_cfg_zero = CameraCfg( + prim_path="/World/CameraZero", offset=CameraCfg.OffsetCfg(pos=(2.5, 2.5, 6.0), rot=(-0.125, 0.362, 0.873, -0.302), convention="ros"), spawn=sim_utils.PinholeCameraCfg().from_intrinsic_matrix( focal_length=38.0, @@ -381,8 +381,19 @@ def test_depth_clipping(self): height=540, width=960, data_types=["distance_to_image_plane", "distance_to_camera"], + depth_clipping_behavior="zero", ) - camera = Camera(camera_cfg) + camera_zero = Camera(camera_cfg_zero) + + camera_cfg_none = copy.deepcopy(camera_cfg_zero) + camera_cfg_none.prim_path = "/World/CameraNone" + camera_cfg_none.depth_clipping_behavior = "none" + camera_none = Camera(camera_cfg_none) + + camera_cfg_max = copy.deepcopy(camera_cfg_zero) + camera_cfg_max.prim_path = "/World/CameraMax" + camera_cfg_max.depth_clipping_behavior = "max" + camera_max = Camera(camera_cfg_max) # Play sim self.sim.reset() @@ -392,17 +403,33 @@ def test_depth_clipping(self): for _ in range(5): self.sim.step() - camera.update(self.dt) - - self.assertTrue( - camera.data.output["distance_to_camera"][camera.data.output["distance_to_camera"] != 0.0].min() >= 0.1 - ) - self.assertTrue(camera.data.output["distance_to_camera"].max() <= 10.0) - self.assertTrue( - camera.data.output["distance_to_image_plane"][camera.data.output["distance_to_image_plane"] != 0.0].min() - >= 0.1 - ) - self.assertTrue(camera.data.output["distance_to_image_plane"].max() <= 10.0) + camera_zero.update(self.dt) + camera_none.update(self.dt) + camera_max.update(self.dt) + + # none clipping should contain inf values + self.assertTrue(torch.isinf(camera_none.data.output["distance_to_camera"]).any()) + self.assertTrue(torch.isinf(camera_none.data.output["distance_to_image_plane"]).any()) + self.assertTrue(camera_none.data.output["distance_to_camera"][~torch.isinf(camera_none.data.output["distance_to_camera"])].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_none.data.output["distance_to_camera"][~torch.isinf(camera_none.data.output["distance_to_camera"])].max() <= camera_cfg_zero.spawn.clipping_range[1]) + self.assertTrue(camera_none.data.output["distance_to_image_plane"][~torch.isinf(camera_none.data.output["distance_to_image_plane"])].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_none.data.output["distance_to_image_plane"][~torch.isinf(camera_none.data.output["distance_to_camera"])].max() <= camera_cfg_zero.spawn.clipping_range[1]) + + # zero clipping should result in zero values + self.assertTrue(torch.all(camera_zero.data.output["distance_to_camera"][torch.isinf(camera_none.data.output["distance_to_camera"])] == 0.0)) + self.assertTrue(torch.all(camera_zero.data.output["distance_to_image_plane"][torch.isinf(camera_none.data.output["distance_to_image_plane"])] == 0.0)) + self.assertTrue(camera_zero.data.output["distance_to_camera"][camera_zero.data.output["distance_to_camera"] != 0.0].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_zero.data.output["distance_to_camera"].max() <= camera_cfg_zero.spawn.clipping_range[1]) + self.assertTrue(camera_zero.data.output["distance_to_image_plane"][camera_zero.data.output["distance_to_image_plane"] != 0.0].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_zero.data.output["distance_to_image_plane"].max() <= camera_cfg_zero.spawn.clipping_range[1]) + + # max clipping should result in max values + self.assertTrue(torch.all(camera_max.data.output["distance_to_camera"][torch.isinf(camera_none.data.output["distance_to_camera"])] == camera_cfg_zero.spawn.clipping_range[1])) + self.assertTrue(torch.all(camera_max.data.output["distance_to_image_plane"][torch.isinf(camera_none.data.output["distance_to_image_plane"])] == camera_cfg_zero.spawn.clipping_range[1])) + self.assertTrue(camera_max.data.output["distance_to_camera"].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_max.data.output["distance_to_camera"].max() <= camera_cfg_zero.spawn.clipping_range[1]) + self.assertTrue(camera_max.data.output["distance_to_image_plane"].min() >= camera_cfg_zero.spawn.clipping_range[0]) + self.assertTrue(camera_max.data.output["distance_to_image_plane"].max() <= camera_cfg_zero.spawn.clipping_range[1]) def test_camera_resolution_all_colorize(self): """Test camera resolution is correctly set for all types with colorization enabled.""" diff --git a/source/extensions/omni.isaac.lab/test/sensors/test_ray_caster_camera.py b/source/extensions/omni.isaac.lab/test/sensors/test_ray_caster_camera.py index 31b655244d..0c918372ee 100644 --- a/source/extensions/omni.isaac.lab/test/sensors/test_ray_caster_camera.py +++ b/source/extensions/omni.isaac.lab/test/sensors/test_ray_caster_camera.py @@ -157,9 +157,13 @@ def test_depth_clipping(self): This test is the same for all camera models to enforce the same clipping behavior. """ + prim_utils.create_prim("/World/CameraZero", "Xform") + prim_utils.create_prim("/World/CameraNone", "Xform") + prim_utils.create_prim("/World/CameraMax", "Xform") + # get camera cfgs - camera_cfg = RayCasterCameraCfg( - prim_path="/World/Camera", + camera_cfg_zero = RayCasterCameraCfg( + prim_path="/World/CameraZero", mesh_prim_paths=["/World/defaultGroundPlane"], offset=RayCasterCameraCfg.OffsetCfg( pos=(2.5, 2.5, 6.0), rot=(-0.125, 0.362, 0.873, -0.302), convention="ros" @@ -172,23 +176,44 @@ def test_depth_clipping(self): ), max_distance=10.0, data_types=["distance_to_image_plane", "distance_to_camera"], + depth_clipping_behavior="zero", ) - camera = RayCasterCamera(camera_cfg) + camera_zero = RayCasterCamera(camera_cfg_zero) + + camera_cfg_none = copy.deepcopy(camera_cfg_zero) + camera_cfg_none.prim_path = "/World/CameraNone" + camera_cfg_none.depth_clipping_behavior = "none" + camera_none = RayCasterCamera(camera_cfg_none) + + camera_cfg_max = copy.deepcopy(camera_cfg_zero) + camera_cfg_max.prim_path = "/World/CameraMax" + camera_cfg_max.depth_clipping_behavior = "max" + camera_max = RayCasterCamera(camera_cfg_max) # Play sim self.sim.reset() - camera.update(self.dt) - - self.assertTrue( - camera.data.output["distance_to_camera"][camera.data.output["distance_to_camera"] != 0.0].min() >= 0.1 - ) - self.assertTrue(camera.data.output["distance_to_camera"].max() <= 10.0) - self.assertTrue( - camera.data.output["distance_to_image_plane"][camera.data.output["distance_to_image_plane"] != 0.0].min() - >= 0.1 - ) - self.assertTrue(camera.data.output["distance_to_image_plane"].max() <= 10.0) + camera_zero.update(self.dt) + camera_none.update(self.dt) + camera_max.update(self.dt) + + # none clipping should contain inf values + self.assertTrue(torch.isnan(camera_none.data.output["distance_to_camera"]).any()) + self.assertTrue(torch.isnan(camera_none.data.output["distance_to_image_plane"]).any()) + self.assertTrue(camera_none.data.output["distance_to_camera"][~torch.isnan(camera_none.data.output["distance_to_camera"])].max() <= camera_cfg_zero.max_distance) + self.assertTrue(camera_none.data.output["distance_to_image_plane"][~torch.isnan(camera_none.data.output["distance_to_camera"])].max() <= camera_cfg_zero.max_distance) + + # zero clipping should result in zero values + self.assertTrue(torch.all(camera_zero.data.output["distance_to_camera"][torch.isnan(camera_none.data.output["distance_to_camera"])] == 0.0)) + self.assertTrue(torch.all(camera_zero.data.output["distance_to_image_plane"][torch.isnan(camera_none.data.output["distance_to_image_plane"])] == 0.0)) + self.assertTrue(camera_zero.data.output["distance_to_camera"].max() <= camera_cfg_zero.max_distance) + self.assertTrue(camera_zero.data.output["distance_to_image_plane"].max() <= camera_cfg_zero.max_distance) + + # max clipping should result in max values + self.assertTrue(torch.all(camera_max.data.output["distance_to_camera"][torch.isnan(camera_none.data.output["distance_to_camera"])] == camera_cfg_zero.max_distance)) + self.assertTrue(torch.all(camera_max.data.output["distance_to_image_plane"][torch.isnan(camera_none.data.output["distance_to_image_plane"])] == camera_cfg_zero.max_distance)) + self.assertTrue(camera_max.data.output["distance_to_camera"].max() <= camera_cfg_zero.max_distance) + self.assertTrue(camera_max.data.output["distance_to_image_plane"].max() <= camera_cfg_zero.max_distance) def test_camera_init_offset(self): """Test camera initialization with offset using different conventions."""