-
Notifications
You must be signed in to change notification settings - Fork 218
Description
Description
Mismatch in fy calculation (depth → point cloud vs. camera_info)
Description
In Isaac Sim 5.0, the calculation of fy for the depth → point cloud conversion does not match the formula in the documentation.
Docs state:
fy = height * focalLength / verticalAperture
But in the code (OgnIsaacConvertDepthToPointCloud.cpp, line 60):
fy = height * focalLength / (horizontalAperture * (height / width))
This simplifies to:
fy = width * focalLength / horizontalAperture
Which is the same as fx.
That means fx = fy is enforced, which only makes sense if pixels are square:
horizontalAperture / width = verticalAperture / height
Otherwise, camera intrinsics from camera_info (which use verticalAperture directly) will not match the intrinsics used in depth_pcl.
Recommendation
- Update the
read_infoside so it is consistent with how intrinsics are applied in the depth → point cloud conversion. - Clearly document that users must use square pixels (sensor aspect ratio must match image resolution) for things to line up correctly.
References
- Forum discussion: https://forums.developer.nvidia.com/t/bug-ros2-omnigraph-camera-info-camera-intrisics/344939/3
- Depth → point cloud code: OgnIsaacConvertDepthToPointCloud.cpp#L60
IsaacSim/source/extensions/isaacsim.core.nodes/nodes/OgnIsaacConvertDepthToPointCloud.cpp
Line 60 in 07d8dd4
fy = height * db.inputs.focalLength() / (db.inputs.horizontalAperture() * (static_cast<float>(height) / width)); - Camera info helper: camera_info_utils.py#L87
fy = height * focalLength / verticalAperture - Docs (expected formula): https://docs.isaacsim.omniverse.nvidia.com/5.0.0/ros2_tutorials/tutorial_ros2_camera.html
Isaac Sim version
5.0
Operating System (OS)
Ubuntu 24.04
GPU Name
RTX 3080
GPU Driver and CUDA versions
NVIDIA-SMI 550.163.01 Driver Version: 550.163.01 CUDA Version: 12.4
Logs
No response
Additional information
No response