Skip to content

Depth to Point Cloud / Camera Info intrinsics mismatch (fy calculation) #199

@ahamboeck

Description

@ahamboeck

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_info side 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

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

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't workingpending-repo-updateIssue fixed internally, pending repository update to reflect the change

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions