Unverified Commit 7b3ca4ff authored by Pascal Roth's avatar Pascal Roth Committed by GitHub

Updates camera docs with world units and introduces new test for intrinsics (#886)

# Description

Updates the camera docs with SI units and implants a new test to check
that the intrinsic are set correctly for the raycaster camera.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent e7b630f0
Fixed
^^^^^
* Added missing SI units to the documentation of :class:`omni.isaac.lab.sensors.Camera` and
:class:`omni.isaac.lab.sensors.RayCasterCamera`.
* Added test to check :attr:`omni.isaac.lab.sensors.RayCasterCamera.set_intrinsic_matrices`
Changelog Changelog
--------- ---------
......
...@@ -216,7 +216,7 @@ class Camera(SensorBase): ...@@ -216,7 +216,7 @@ class Camera(SensorBase):
Args: Args:
matrices: The intrinsic matrices for the camera. Shape is (N, 3, 3). matrices: The intrinsic matrices for the camera. Shape is (N, 3, 3).
focal_length: Focal length to use when computing aperture values. Defaults to 1.0. focal_length: Focal length to use when computing aperture values (in cm). Defaults to 1.0.
env_ids: A sensor ids to manipulate. Defaults to None, which means all sensor indices. env_ids: A sensor ids to manipulate. Defaults to None, which means all sensor indices.
""" """
# resolve env_ids # resolve env_ids
......
...@@ -70,7 +70,13 @@ class GridPatternCfg(PatternBaseCfg): ...@@ -70,7 +70,13 @@ class GridPatternCfg(PatternBaseCfg):
@configclass @configclass
class PinholeCameraPatternCfg(PatternBaseCfg): class PinholeCameraPatternCfg(PatternBaseCfg):
"""Configuration for a pinhole camera depth image pattern for ray-casting.""" """Configuration for a pinhole camera depth image pattern for ray-casting.
.. caution::
Focal length as well as the aperture sizes and offsets are set as a tenth of the world unit. In our case, the
world unit is meters, so all of these values are in cm. For more information, please check:
https://docs.omniverse.nvidia.com/materials-and-rendering/latest/cameras.html
"""
func: Callable = patterns.pinhole_camera_pattern func: Callable = patterns.pinhole_camera_pattern
...@@ -81,16 +87,15 @@ class PinholeCameraPatternCfg(PatternBaseCfg): ...@@ -81,16 +87,15 @@ class PinholeCameraPatternCfg(PatternBaseCfg):
""" """
horizontal_aperture: float = 20.955 horizontal_aperture: float = 20.955
"""Horizontal aperture (in mm). Defaults to 20.955mm. """Horizontal aperture (in cm). Defaults to 20.955 cm.
Emulates sensor/film width on a camera. Emulates sensor/film width on a camera.
Note: Note:
The default value is the horizontal aperture of a 35 mm spherical projector. The default value is the horizontal aperture of a 35 mm spherical projector.
""" """
vertical_aperture: float | None = None vertical_aperture: float | None = None
"""Vertical aperture (in mm). Defaults to None. r"""Vertical aperture (in cm). Defaults to None.
Emulates sensor/film height on a camera. If None, then the vertical aperture is calculated based on the Emulates sensor/film height on a camera. If None, then the vertical aperture is calculated based on the
horizontal aperture and the aspect ratio of the image to maintain squared pixels. In this case, the vertical horizontal aperture and the aspect ratio of the image to maintain squared pixels. In this case, the vertical
......
...@@ -126,7 +126,7 @@ class RayCasterCamera(RayCaster): ...@@ -126,7 +126,7 @@ class RayCasterCamera(RayCaster):
Args: Args:
matrices: The intrinsic matrices for the camera. Shape is (N, 3, 3). matrices: The intrinsic matrices for the camera. Shape is (N, 3, 3).
focal_length: Focal length to use when computing aperture values. Defaults to 1.0. focal_length: Focal length to use when computing aperture values (in cm). Defaults to 1.0.
env_ids: A sensor ids to manipulate. Defaults to None, which means all sensor indices. env_ids: A sensor ids to manipulate. Defaults to None, which means all sensor indices.
""" """
# resolve env_ids # resolve env_ids
......
...@@ -5,10 +5,12 @@ ...@@ -5,10 +5,12 @@
"""Configuration for the ray-cast camera sensor.""" """Configuration for the ray-cast camera sensor."""
from dataclasses import MISSING
from typing import Literal from typing import Literal
from omni.isaac.lab.utils import configclass from omni.isaac.lab.utils import configclass
from .patterns import PinholeCameraPatternCfg
from .ray_caster_camera import RayCasterCamera from .ray_caster_camera import RayCasterCamera
from .ray_caster_cfg import RayCasterCfg from .ray_caster_cfg import RayCasterCfg
...@@ -44,6 +46,9 @@ class RayCasterCameraCfg(RayCasterCfg): ...@@ -44,6 +46,9 @@ class RayCasterCameraCfg(RayCasterCfg):
data_types: list[str] = ["distance_to_image_plane"] data_types: list[str] = ["distance_to_image_plane"]
"""List of sensor names/types to enable for the camera. Defaults to ["distance_to_image_plane"].""" """List of sensor names/types to enable for the camera. Defaults to ["distance_to_image_plane"]."""
pattern_cfg: PinholeCameraPatternCfg = MISSING
"""The pattern that defines the local ray starting positions and directions in a pinhole camera pattern."""
def __post_init__(self): def __post_init__(self):
# for cameras, this quantity should be False always. # for cameras, this quantity should be False always.
self.attach_yaw_only = False self.attach_yaw_only = False
...@@ -20,6 +20,10 @@ class PinholeCameraCfg(SpawnerCfg): ...@@ -20,6 +20,10 @@ class PinholeCameraCfg(SpawnerCfg):
For more information on the parameters, please refer to the `camera documentation <https://docs.omniverse.nvidia.com/materials-and-rendering/latest/cameras.html>`__. For more information on the parameters, please refer to the `camera documentation <https://docs.omniverse.nvidia.com/materials-and-rendering/latest/cameras.html>`__.
..note ::
Focal length as well as the aperture sizes and offsets are set as a tenth of the world unit. In our case, the
world unit is Meter s.t. all of these values are set in cm.
.. note:: .. note::
The default values are taken from the `Replicator camera <https://docs.omniverse.nvidia.com/py/replicator/1.9.8/source/extensions/omni.replicator.core/docs/API.html#omni.replicator.core.create.camera>`__ The default values are taken from the `Replicator camera <https://docs.omniverse.nvidia.com/py/replicator/1.9.8/source/extensions/omni.replicator.core/docs/API.html#omni.replicator.core.create.camera>`__
function. function.
...@@ -60,7 +64,7 @@ class PinholeCameraCfg(SpawnerCfg): ...@@ -60,7 +64,7 @@ class PinholeCameraCfg(SpawnerCfg):
""" """
horizontal_aperture: float = 20.955 horizontal_aperture: float = 20.955
"""Horizontal aperture (in mm). Defaults to 20.955mm. """Horizontal aperture (in cm). Defaults to 20.955 cm.
Emulates sensor/film width on a camera. Emulates sensor/film width on a camera.
......
...@@ -739,6 +739,82 @@ class TestWarpCamera(unittest.TestCase): ...@@ -739,6 +739,82 @@ class TestWarpCamera(unittest.TestCase):
rtol=5e-6, rtol=5e-6,
) )
def test_output_equal_to_usd_camera_when_intrinsics_set(self):
"""
Test that the output of the ray caster camera is equal to the output of the usd camera when both are placed
under an XForm prim and an intrinsic matrix is set.
"""
camera_pattern_cfg = patterns.PinholeCameraPatternCfg(
focal_length=24.0,
horizontal_aperture=20.955,
height=540,
width=960,
)
camera_cfg_warp = RayCasterCameraCfg(
prim_path="/World/Camera",
mesh_prim_paths=["/World/defaultGroundPlane"],
update_period=0,
offset=RayCasterCameraCfg.OffsetCfg(pos=(0.0, 0.0, 0.0), rot=(1.0, 0.0, 0.0, 0.0)),
debug_vis=False,
pattern_cfg=camera_pattern_cfg,
data_types=["distance_to_camera"],
)
camera_warp = RayCasterCamera(camera_cfg_warp)
# create usd camera
camera_cfg_usd = CameraCfg(
height=540,
width=960,
prim_path="/World/Camera_usd",
update_period=0,
data_types=["distance_to_camera"],
spawn=PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(1e-4, 1.0e5)
),
)
camera_usd = Camera(camera_cfg_usd)
# play sim
self.sim.reset()
self.sim.play()
# set intrinsic matrix
# NOTE: extend the test to cover aperture offsets once supported by the usd camera
intrinsic_matrix = torch.tensor(
[[380.0831, 0.0, camera_cfg_usd.width / 2, 0.0, 380.0831, camera_cfg_usd.height / 2, 0.0, 0.0, 1.0]],
device=camera_warp.device,
).reshape(1, 3, 3)
camera_warp.set_intrinsic_matrices(intrinsic_matrix, focal_length=10)
camera_usd.set_intrinsic_matrices(intrinsic_matrix, focal_length=10)
# set camera position
camera_warp.set_world_poses_from_view(
eyes=torch.tensor([[0.0, 0.0, 5.0]], device=camera_warp.device),
targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_warp.device),
)
camera_usd.set_world_poses_from_view(
eyes=torch.tensor([[0.0, 0.0, 5.0]], device=camera_usd.device),
targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_usd.device),
)
# perform steps
for _ in range(5):
self.sim.step()
# update camera
camera_usd.update(self.dt)
camera_warp.update(self.dt)
# check image data
torch.testing.assert_close(
camera_usd.data.output["distance_to_camera"],
camera_warp.data.output["distance_to_camera"],
rtol=5e-3,
atol=1e-4,
)
if __name__ == "__main__": if __name__ == "__main__":
run_tests() run_tests()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment