Skip to content

Conversation

@ahamboeck
Copy link

Align camera_info intrinsics with depth → point cloud (square pixels assumption)

Summary

This PR updates the fy calculation in camera_info_utils.py so that it matches the depth → point cloud implementation (OgnIsaacConvertDepthToPointCloud.cpp).

Previously, camera_info_utils.py calculated fy using the vertical aperture:

fy = height * focalLength / verticalAperture

But in depth → point cloud, fy was already implemented as:

// We assume that we have square pixels so fy = height * focalLength / (horizontalAperture * (height / width))
fx = width * focalLength / horizontalAperture;
fy = height * focalLength / (horizontalAperture * (height / width));
cx = width * 0.5f;
cy = height * 0.5f;

This simplifies to:

fy = width * focalLength / horizontalAperture

which makes fy the same as fx.

With this PR, camera_info_utils.py now uses the same formula as the depth → point cloud path, enforcing the square pixel assumption consistently.

Why

  • Avoids mismatched intrinsics between camera_info and depth_pcl.
  • Makes the assumption of square pixels explicit (sensor aspect ratio must match resolution).
  • Keeps behavior consistent across both camera_info and point cloud generation.

Recommendation

  • Update the documentation to clearly state that square pixels must be used.
  • Clarify that both fx and fy are derived from the horizontal aperture under this assumption.

References

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant