Expand description
Point cloud colorization from registered RGB images.
A “registered” RGB image is one whose camera pose (position and orientation relative to the point cloud coordinate frame) is known. Given the camera intrinsics and extrinsics, every 3-D point can be projected onto the image plane and the corresponding pixel color assigned to it.
§Pipeline
- Transform each 3-D point from world space into camera space using the provided world-to-camera isometry.
- Project the camera-space point onto the image plane with the pinhole camera model.
- Discard points that lie behind the camera (negative depth) or whose projected pixel falls outside the image.
- Sample the pixel color — nearest-neighbour or bilinear — and write it
into the output
ColoredPoint3f.
§Multi-image support
colorize_from_images accepts a slice of (image, intrinsics, pose)
triples. Each 3-D point is colored by the first image that can see it.
Images should therefore be supplied in order of preference (e.g. most
frontal camera first).
Structs§
- Camera
Intrinsics - Pinhole camera intrinsic parameters.
- Colorization
Config - Configuration for
colorize_point_cloud. - Colorization
Result - Summary statistics returned by
colorize_point_cloud. - RgbImage
View - A borrowed, tightly-packed RGB image (row-major, 3 bytes per pixel).
Enums§
- Interpolation
Mode - Interpolation strategy when sampling pixel colors.
Functions§
- colorize_
from_ images - Colorize a point cloud from multiple registered RGB images.
- colorize_
point_ cloud - Colorize a point cloud from a single registered RGB image.