Unverified Commit 871e26aa authored by James Tigue's avatar James Tigue Committed by GitHub

Fixes how camera intrinsics are used for creation and update (#1624)

# Description

<!--
Thank you for your interest in sending a pull request. Please make sure
to check the contribution guidelines.

Link:
https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html
-->

This PR changes how the camera intrinsic matrix is used to create usd
cameras and updated from usd camera parameters so that if the intrinsic
matrix is accessed in CameraData it will be the same as the intrinsic
matrix used to create the USD camera.

Fixes # (issue)

<!-- As a practice, it is recommended to open an issue to have
discussions on the proposed pull request.
This makes it easier for the community to keep track of what is being
developed or added, and if a given feature
is demanded by more than one party. -->

## Type of change

<!-- As you go through the list, delete the ones that are not
applicable. -->

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

## Screenshots

Please attach before and after screenshots of the change if applicable.

<!--
Example:

| Before | After |
| ------ | ----- |
| _gif/png before_ | _gif/png after_ |

To upload images to a PR -- simply drag and drop an image while in edit
mode and it should upload the image directly. You can then paste that
source into the above before/after sections.
-->

## 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
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] 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

<!--
As you go through the checklist above, you can mark something as done by
putting an x character in it

For example,
- [x] I have done this task
- [ ] I have not done this task
-->
parent 212de427
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.39.0"
version = "0.39.2"
# Description
title = "Isaac Lab framework for Robot Learning"
......
Changelog
---------
0.39.2 (2025-05-15)
~~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Fixed :meth:`omni.isaac.lab.sensors.camera.camera.Camera.set_intrinsic_matrices` preventing setting of unused USD
camera parameters.
* Fixed :meth:`omni.isaac.lab.sensors.camera.camera.Camera._update_intrinsic_matrices` preventing unused USD camera
parameters from being used to calculate :attr:`omni.isaac.lab.sensors.camera.CameraData.intrinsic_matrices`
* Fixed :meth:`omni.isaac.lab.spawners.sensors.sensors_cfg.PinholeCameraCfg.from_intrinsic_matrix` preventing setting of
unused USD camera parameters.
0.39.1 (2025-05-14)
~~~~~~~~~~~~~~~~~~~
......
......@@ -21,6 +21,7 @@ from isaacsim.core.version import get_version
from pxr import Sdf, UsdGeom
import isaaclab.sim as sim_utils
import isaaclab.utils.sensors as sensor_utils
from isaaclab.utils import to_camel_case
from isaaclab.utils.array import convert_to_torch
from isaaclab.utils.math import (
......@@ -221,11 +222,11 @@ class Camera(SensorBase):
"""
def set_intrinsic_matrices(
self, matrices: torch.Tensor, focal_length: float = 1.0, env_ids: Sequence[int] | None = None
self, matrices: torch.Tensor, focal_length: float | None = None, env_ids: Sequence[int] | None = None
):
"""Set parameters of the USD camera from its intrinsic matrix.
The intrinsic matrix and focal length are used to set the following parameters to the USD camera:
The intrinsic matrix is used to set the following parameters to the USD camera:
- ``focal_length``: The focal length of the camera.
- ``horizontal_aperture``: The horizontal aperture of the camera.
......@@ -241,7 +242,8 @@ class Camera(SensorBase):
Args:
matrices: The intrinsic matrices for the camera. Shape is (N, 3, 3).
focal_length: Focal length to use when computing aperture values (in cm). Defaults to 1.0.
focal_length: Perspective focal length (in cm) used to calculate pixel size. Defaults to None. If None,
focal_length will be calculated 1 / width.
env_ids: A sensor ids to manipulate. Defaults to None, which means all sensor indices.
"""
# resolve env_ids
......@@ -254,27 +256,12 @@ class Camera(SensorBase):
matrices = np.asarray(matrices, dtype=float)
# iterate over env_ids
for i, intrinsic_matrix in zip(env_ids, matrices):
# extract parameters from matrix
f_x = intrinsic_matrix[0, 0]
c_x = intrinsic_matrix[0, 2]
f_y = intrinsic_matrix[1, 1]
c_y = intrinsic_matrix[1, 2]
# get viewport parameters
height, width = self.image_shape
height, width = float(height), float(width)
# resolve parameters for usd camera
params = {
"focal_length": focal_length,
"horizontal_aperture": width * focal_length / f_x,
"vertical_aperture": height * focal_length / f_y,
"horizontal_aperture_offset": (c_x - width / 2) / f_x,
"vertical_aperture_offset": (c_y - height / 2) / f_y,
}
# TODO: Adjust to handle aperture offsets once supported by omniverse
# Internal ticket from rendering team: OM-42611
if params["horizontal_aperture_offset"] > 1e-4 or params["vertical_aperture_offset"] > 1e-4:
omni.log.warn("Camera aperture offsets are not supported by Omniverse. These parameters are ignored.")
params = sensor_utils.convert_camera_intrinsics_to_usd(
intrinsic_matrix=intrinsic_matrix.reshape(-1), height=height, width=width, focal_length=focal_length
)
# change data for corresponding camera index
sensor_prim = self._sensor_prims[i]
......@@ -599,18 +586,17 @@ class Camera(SensorBase):
# Get corresponding sensor prim
sensor_prim = self._sensor_prims[i]
# get camera parameters
# currently rendering does not use aperture offsets or vertical aperture
focal_length = sensor_prim.GetFocalLengthAttr().Get()
horiz_aperture = sensor_prim.GetHorizontalApertureAttr().Get()
vert_aperture = sensor_prim.GetVerticalApertureAttr().Get()
horiz_aperture_offset = sensor_prim.GetHorizontalApertureOffsetAttr().Get()
vert_aperture_offset = sensor_prim.GetVerticalApertureOffsetAttr().Get()
# get viewport parameters
height, width = self.image_shape
# extract intrinsic parameters
f_x = (width * focal_length) / horiz_aperture
f_y = (height * focal_length) / vert_aperture
c_x = width * 0.5 + horiz_aperture_offset * f_x
c_y = height * 0.5 + vert_aperture_offset * f_y
f_y = f_x
c_x = width * 0.5
c_y = height * 0.5
# create intrinsic matrix for depth linear
self._data.intrinsic_matrices[i, 0, 0] = f_x
self._data.intrinsic_matrices[i, 0, 2] = c_x
......
......@@ -8,6 +8,7 @@ from __future__ import annotations
from collections.abc import Callable
from typing import Literal
import isaaclab.utils.sensors as sensor_utils
from isaaclab.sim.spawners.spawner_cfg import SpawnerCfg
from isaaclab.utils import configclass
......@@ -102,7 +103,7 @@ class PinholeCameraCfg(SpawnerCfg):
width: int,
height: int,
clipping_range: tuple[float, float] = (0.01, 1e6),
focal_length: float = 24.0,
focal_length: float | None = None,
focus_distance: float = 400.0,
f_stop: float = 0.0,
projection_type: str = "pinhole",
......@@ -129,7 +130,8 @@ class PinholeCameraCfg(SpawnerCfg):
width: Width of the image (in pixels).
height: Height of the image (in pixels).
clipping_range: Near and far clipping distances (in m). Defaults to (0.01, 1e6).
focal_length: Perspective focal length (in cm). Defaults to 24.0 cm.
focal_length: Perspective focal length (in cm) used to calculate pixel size. Defaults to None. If None
focal_length will be calculated 1 / width.
focus_distance: Distance from the camera to the focus plane (in m). Defaults to 400.0 m.
f_stop: Lens aperture. Defaults to 0.0, which turns off focusing.
projection_type: Type of projection to use for the camera. Defaults to "pinhole".
......@@ -142,27 +144,20 @@ class PinholeCameraCfg(SpawnerCfg):
if projection_type != "pinhole":
raise NotImplementedError("Only pinhole projection type is supported.")
# extract parameters from matrix
f_x = intrinsic_matrix[0]
c_x = intrinsic_matrix[2]
f_y = intrinsic_matrix[4]
c_y = intrinsic_matrix[5]
# resolve parameters for usd camera
horizontal_aperture = width * focal_length / f_x
vertical_aperture = height * focal_length / f_y
horizontal_aperture_offset = (c_x - width / 2) / f_x
vertical_aperture_offset = (c_y - height / 2) / f_y
usd_camera_params = sensor_utils.convert_camera_intrinsics_to_usd(
intrinsic_matrix=intrinsic_matrix, height=height, width=width, focal_length=focal_length
)
return cls(
projection_type=projection_type,
clipping_range=clipping_range,
focal_length=focal_length,
focal_length=usd_camera_params["focal_length"],
focus_distance=focus_distance,
f_stop=f_stop,
horizontal_aperture=horizontal_aperture,
vertical_aperture=vertical_aperture,
horizontal_aperture_offset=horizontal_aperture_offset,
vertical_aperture_offset=vertical_aperture_offset,
horizontal_aperture=usd_camera_params["horizontal_aperture"],
vertical_aperture=usd_camera_params["vertical_aperture"],
horizontal_aperture_offset=usd_camera_params["horizontal_aperture_offset"],
vertical_aperture_offset=usd_camera_params["vertical_aperture_offset"],
lock_camera=lock_camera,
)
......
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import omni
def convert_camera_intrinsics_to_usd(
intrinsic_matrix: list[float], width: int, height: int, focal_length: float | None = None
) -> dict:
"""Creates USD camera properties from camera intrinsics and resolution.
Args:
intrinsic_matrix: Intrinsic matrix of the camera in row-major format.
The matrix is defined as [f_x, 0, c_x, 0, f_y, c_y, 0, 0, 1]. Shape is (9,).
width: Width of the image (in pixels).
height: Height of the image (in pixels).
focal_length: Perspective focal length (in cm) used to calculate pixel size. Defaults to None. If None
focal_length will be calculated 1 / width.
Returns:
A dictionary of USD camera parameters for focal_length, horizontal_aperture, vertical_aperture,
horizontal_aperture_offset, and vertical_aperture_offset.
"""
usd_params = dict
# extract parameters from matrix
f_x = intrinsic_matrix[0]
f_y = intrinsic_matrix[4]
c_x = intrinsic_matrix[2]
c_y = intrinsic_matrix[5]
# warn about non-square pixels
if abs(f_x - f_y) > 1e-4:
omni.log.warn("Camera non square pixels are not supported by Omniverse. The average of f_x and f_y are used.")
# warn about aperture offsets
if abs((c_x - float(width) / 2) > 1e-4 or (c_y - float(height) / 2) > 1e-4):
omni.log.warn(
"Camera aperture offsets are not supported by Omniverse. c_x and c_y will be half of width and height"
)
# calculate usd camera parameters
# pixel_size does not need to be exact it is just used for consistent sizing of aperture and focal_length
# https://docs.omniverse.nvidia.com/isaacsim/latest/features/sensors_simulation/isaac_sim_sensors_camera.html#calibrated-camera-sensors
if focal_length is None:
pixel_size = 1 / float(width)
else:
pixel_size = focal_length / ((f_x + f_y) / 2)
usd_params = {
"horizontal_aperture": pixel_size * float(width),
"vertical_aperture": pixel_size * float(height),
"focal_length": pixel_size * (f_x + f_y) / 2, # The focal length in mm
"horizontal_aperture_offset": 0.0,
"vertical_aperture_offset": 0.0,
}
return usd_params
......@@ -43,11 +43,15 @@ QUAT_WORLD = (-0.3647052, -0.27984815, -0.1159169, 0.88047623)
# NOTE: setup and teardown are own function to allow calling them in the tests
# resolutions
HEIGHT = 240
WIDTH = 320
def setup() -> tuple[sim_utils.SimulationContext, CameraCfg, float]:
camera_cfg = CameraCfg(
height=128,
width=128,
height=HEIGHT,
width=WIDTH,
prim_path="/World/Camera",
update_period=0,
data_types=["distance_to_image_plane"],
......@@ -292,15 +296,15 @@ def test_camera_init_intrinsic_matrix(setup_sim_camera):
camera_1 = Camera(cfg=camera_cfg)
# initialize from intrinsic matrix
intrinsic_camera_cfg = CameraCfg(
height=128,
width=128,
height=HEIGHT,
width=WIDTH,
prim_path="/World/Camera_2",
update_period=0,
data_types=["distance_to_image_plane"],
spawn=sim_utils.PinholeCameraCfg.from_intrinsic_matrix(
intrinsic_matrix=intrinsic_matrix,
width=128,
height=128,
width=WIDTH,
height=HEIGHT,
focal_length=24.0,
focus_distance=400.0,
clipping_range=(0.1, 1.0e5),
......@@ -396,7 +400,7 @@ def test_intrinsic_matrix(setup_sim_camera):
# play sim
sim.reset()
# Desired properties (obtained from realsense camera at 320x240 resolution)
rs_intrinsic_matrix = [229.31640625, 0.0, 164.810546875, 0.0, 229.826171875, 122.1650390625, 0.0, 0.0, 1.0]
rs_intrinsic_matrix = [229.8, 0.0, 160.0, 0.0, 229.8, 120.0, 0.0, 0.0, 1.0]
rs_intrinsic_matrix = torch.tensor(rs_intrinsic_matrix, device=camera.device).reshape(3, 3).unsqueeze(0)
# Set matrix into simulator
camera.set_intrinsic_matrices(rs_intrinsic_matrix.clone())
......@@ -414,11 +418,10 @@ def test_intrinsic_matrix(setup_sim_camera):
# update camera
camera.update(dt)
# Check that matrix is correct
# TODO: This is not correctly setting all values in the matrix since the
# vertical aperture and aperture offsets are not being set correctly
# This is a bug in the simulator.
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])
torch.testing.assert_close(rs_intrinsic_matrix[0, 1, 1], camera.data.intrinsic_matrices[0, 1, 1])
torch.testing.assert_close(rs_intrinsic_matrix[0, 0, 2], camera.data.intrinsic_matrices[0, 0, 2])
torch.testing.assert_close(rs_intrinsic_matrix[0, 1, 2], camera.data.intrinsic_matrices[0, 1, 2])
def test_depth_clipping(setup_sim_camera):
......
......@@ -1496,8 +1496,6 @@ def test_output_equal_to_usd_camera_intrinsics(setup_camera):
intrinsic_matrix=intrinsics,
height=540,
width=960,
focal_length=38.0,
# clipping_range=(0.01, 20),
),
height=540,
width=960,
......@@ -1510,8 +1508,6 @@ def test_output_equal_to_usd_camera_intrinsics(setup_camera):
intrinsic_matrix=intrinsics,
height=540,
width=960,
focal_length=38.0,
# clipping_range=(0.01, 20),
),
height=540,
width=960,
......
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