Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds option to change the clipping behavior for all Cameras and unifies the default #891

Open
wants to merge 42 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 39 commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
8c671ba
add intrinsic matrix to initial config
pascal-roth Jul 2, 2024
29c6be4
some fixes
pascal-roth Jul 2, 2024
5e78e20
add tests for new initialization, change to classmethod
pascal-roth Jul 2, 2024
cf3e9f9
adjust changelog
pascal-roth Jul 2, 2024
3e7f833
Apply suggestions from code review
pascal-roth Jul 3, 2024
b369236
add more docs
pascal-roth Jul 3, 2024
9e99d0e
Merge branch 'feature/cam-init-intrinsic-matrix' of github.com:isaac-…
pascal-roth Jul 3, 2024
d5e729f
fixes
pascal-roth Jul 3, 2024
4801278
allow setting of vertical aperture (bugfix as never adjusted for usd …
pascal-roth Jul 3, 2024
71a37b8
formatter
pascal-roth Jul 3, 2024
5ead7d4
Merge branch 'main' into feature/cam-init-intrinsic-matrix
pascal-roth Jul 28, 2024
ffea731
Merge branch 'main' into feature/cam-init-intrinsic-matrix
pascal-roth Aug 15, 2024
06dc697
fix
pascal-roth Aug 16, 2024
20f6b48
formatter
pascal-roth Aug 16, 2024
8760a0f
Merge branch 'main' into feature/cam-init-intrinsic-matrix
pascal-roth Aug 16, 2024
603567e
changlog
pascal-roth Aug 16, 2024
076e767
remove stereolabs
pascal-roth Aug 16, 2024
9ea0c7b
fix
pascal-roth Aug 16, 2024
68ef701
remove change
pascal-roth Aug 16, 2024
1a6ade2
carb warn
pascal-roth Aug 17, 2024
fe86869
add intrinsics test to tiled camera
pascal-roth Aug 28, 2024
559466c
Merge branch 'feature/cam-init-intrinsic-matrix' of github.com:isaac-…
pascal-roth Aug 28, 2024
8b512d3
unifty clipping behavior
pascal-roth Aug 28, 2024
f643d93
changelog and formatter
pascal-roth Aug 28, 2024
00d7979
Merge branch 'main' into fix/cam-clipping
pascal-roth Aug 29, 2024
df67989
forgotten changes
pascal-roth Aug 29, 2024
8e04b28
fix
pascal-roth Aug 29, 2024
f1bf49a
rename
pascal-roth Sep 1, 2024
7edfd04
Merge branch 'main' into fix/cam-clipping
pascal-roth Sep 1, 2024
0289eee
wip
pascal-roth Sep 24, 2024
aafa60d
fix test and format
pascal-roth Sep 28, 2024
5feb179
Merge branch 'main' into fix/cam-clipping
pascal-roth Sep 28, 2024
ead100a
formatter
pascal-roth Sep 28, 2024
e58e9ba
cleanup changelog
pascal-roth Sep 28, 2024
c5a162a
Merge branch 'main' into fix/cam-clipping
Dhoeller19 Oct 31, 2024
a8d040d
improve note
pascal-roth Nov 1, 2024
a29eb3b
Added clipping to tiled camera
Dhoeller19 Nov 4, 2024
40335d3
Merge branch 'main' into fix/cam-clipping
Dhoeller19 Nov 4, 2024
ef37265
Added condition on tiled camera clipping test
Dhoeller19 Nov 4, 2024
7e096b4
Merge branch 'main' into fix/cam-clipping
Dhoeller19 Nov 4, 2024
f0e8bba
Merge branch 'main' into fix/cam-clipping
Dhoeller19 Nov 5, 2024
f4a790f
Merge branch 'main' into fix/cam-clipping
pascal-roth Nov 6, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion source/extensions/omni.isaac.lab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.27.12"
version = "0.27.13"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
19 changes: 19 additions & 0 deletions source/extensions/omni.isaac.lab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,25 @@
Changelog
---------

0.27.13 (2024-09-28)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added option to define the clipping behavior for depth images generated by
:class:`omni.isaac.lab.sensors.ray_caster.RayCasterCamera` and :class:`omni.isaac.lab.sensors.ray_caster.Camera`

Changed
^^^^^^^

* Unified the clipping behavior for the depth images of all camera implementations. Per default, all values exceeding
the range are clipped to zero for both ``distance_to_image_plane`` and ``distance_to_camera`` depth images. Prev.
:class:`omni.isaac.lab.sensors.ray_caster.RayCasterCamera` clipped the values to the maximum value of the depth image,
:class:`omni.isaac.lab.sensors.ray_caster.Camera` did not clip them and had a different behavior for both types, and
:class:`omni.isaac.lab.sensors.ray_caster.TiledCamera` clipped the values to zero.


0.27.12 (2024-01-04)
~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -513,6 +513,19 @@ def _update_buffers_impl(self, env_ids: Sequence[int]):
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]
)

"""
Private Helpers
Expand Down Expand Up @@ -631,6 +644,19 @@ def _create_annotator_data(self):
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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,14 @@ class OffsetCfg:
asset is already present in the scene.
"""

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``.
"""

data_types: list[str] = ["rgb"]
"""List of sensor names/types to enable for the camera. Defaults to ["rgb"].

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -279,6 +279,22 @@ def _update_buffers_impl(self, env_ids: Sequence[int]):
if data_type == "rgba" and "rgb" in self.cfg.data_types:
self._data.output["rgb"] = self._data.output["rgba"][..., :3]

# 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 data_type == "distance_to_camera":
self._data.output[data_type][
self._data.output[data_type] > self.cfg.spawn.clipping_range[1]
] = torch.inf
# apply defined clipping behavior
if (
data_type == "distance_to_camera" or data_type == "distance_to_image_plane" or data_type == "depth"
) and self.cfg.depth_clipping_behavior != "none":
self._data.output[data_type][torch.isinf(self._data.output[data_type])] = (
0.0 if self.cfg.depth_clipping_behavior == "zero" else self.cfg.spawn.clipping_range[1]
)

"""
Private Helpers
"""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,14 +297,23 @@ def _update_buffers_impl(self, env_ids: Sequence[int]):
)
)[:, :, 0]
# apply the maximum distance after the transformation
distance_to_image_plane = torch.clip(distance_to_image_plane, max=self.cfg.max_distance)
if self.cfg.depth_clipping_behavior == "max":
distance_to_image_plane = torch.clip(distance_to_image_plane, max=self.cfg.max_distance)
distance_to_image_plane[torch.isnan(distance_to_image_plane)] = self.cfg.max_distance
elif self.cfg.depth_clipping_behavior == "zero":
distance_to_image_plane[distance_to_image_plane > self.cfg.max_distance] = 0.0
distance_to_image_plane[torch.isnan(distance_to_image_plane)] = 0.0
self._data.output["distance_to_image_plane"][env_ids] = distance_to_image_plane.view(
-1, *self.image_shape, 1
)

if "distance_to_camera" in self.cfg.data_types:
self._data.output["distance_to_camera"][env_ids] = torch.clip(
ray_depth.view(-1, *self.image_shape, 1), max=self.cfg.max_distance
)
if self.cfg.depth_clipping_behavior == "max":
ray_depth = torch.clip(ray_depth, max=self.cfg.max_distance)
elif self.cfg.depth_clipping_behavior == "zero":
ray_depth[ray_depth > self.cfg.max_distance] = 0.0
pascal-roth marked this conversation as resolved.
Show resolved Hide resolved
self._data.output["distance_to_camera"][env_ids] = ray_depth.view(-1, *self.image_shape, 1)

if "normals" in self.cfg.data_types:
self._data.output["normals"][env_ids] = ray_normal.view(-1, *self.image_shape, 3)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,15 @@ 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"
"""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`` for ``distance_to_camera`` and ``nan``
for ``distance_to_image_plane`` data type.
"""

pattern_cfg: PinholeCameraPatternCfg = MISSING
"""The pattern that defines the local ray starting positions and directions in a pinhole camera pattern."""

Expand Down
131 changes: 131 additions & 0 deletions source/extensions/omni.isaac.lab/test/sensors/test_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,137 @@ def test_intrinsic_matrix(self):
torch.testing.assert_close(rs_intrinsic_matrix[0, 0, 0], camera.data.intrinsic_matrices[0, 0, 0])
# torch.testing.assert_close(rs_intrinsic_matrix[0, 1, 1], camera.data.intrinsic_matrices[0, 1, 1])

def test_depth_clipping(self):
"""Test depth clipping.

.. note::

pascal-roth marked this conversation as resolved.
Show resolved Hide resolved
This test is the same for all camera models to enforce the same clipping behavior.
"""
# get camera cfgs
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,
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=(0.1, 10),
),
height=540,
width=960,
data_types=["distance_to_image_plane", "distance_to_camera"],
depth_clipping_behavior="zero",
)
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()

# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
for _ in range(5):
self.sim.step()

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."""
# Add all types
Expand Down
Loading
Loading