Skip to main content

depth_to_pointcloud

Function depth_to_pointcloud 

Source
pub fn depth_to_pointcloud(
    depth: &Array2<f32>,
    fx: f64,
    fy: f64,
    cx: f64,
    cy: f64,
    depth_scale: f64,
) -> PointCloud
Expand description

Unproject a depth image into a 3D point cloud using pinhole camera intrinsics.

§Arguments

  • depth – H×W depth image in metres (0.0 means invalid).
  • fx, fy – Focal lengths in pixels.
  • cx, cy – Principal point in pixels.
  • depth_scale – Multiply raw pixel values by this factor to get metres (use 1.0 when values are already in metres).

§Returns

A PointCloud with one point per valid (non-zero) depth pixel.