Skip to main content

threecrate_algorithms/
colorization.rs

1//! Point cloud colorization from registered RGB images.
2//!
3//! A "registered" RGB image is one whose camera pose (position and orientation
4//! relative to the point cloud coordinate frame) is known.  Given the camera
5//! intrinsics and extrinsics, every 3-D point can be projected onto the image
6//! plane and the corresponding pixel color assigned to it.
7//!
8//! # Pipeline
9//!
10//! 1. Transform each 3-D point from world space into camera space using the
11//!    provided world-to-camera isometry.
12//! 2. Project the camera-space point onto the image plane with the pinhole
13//!    camera model.
14//! 3. Discard points that lie behind the camera (negative depth) or whose
15//!    projected pixel falls outside the image.
16//! 4. Sample the pixel color — nearest-neighbour or bilinear — and write it
17//!    into the output [`ColoredPoint3f`].
18//!
19//! # Multi-image support
20//!
21//! [`colorize_from_images`] accepts a slice of `(image, intrinsics, pose)`
22//! triples.  Each 3-D point is colored by the *first* image that can see it.
23//! Images should therefore be supplied in order of preference (e.g. most
24//! frontal camera first).
25
26use nalgebra::Isometry3;
27use rayon::prelude::*;
28use threecrate_core::{ColoredPoint3f, Point3f, PointCloud, Result, Error};
29
30// ---------------------------------------------------------------------------
31// Public types
32// ---------------------------------------------------------------------------
33
34/// Pinhole camera intrinsic parameters.
35#[derive(Debug, Clone, Copy)]
36pub struct CameraIntrinsics {
37    /// Horizontal focal length in pixels.
38    pub fx: f32,
39    /// Vertical focal length in pixels.
40    pub fy: f32,
41    /// Horizontal principal-point offset (pixels from left edge).
42    pub cx: f32,
43    /// Vertical principal-point offset (pixels from top edge).
44    pub cy: f32,
45}
46
47/// A borrowed, tightly-packed RGB image (row-major, 3 bytes per pixel).
48#[derive(Debug, Clone, Copy)]
49pub struct RgbImageView<'a> {
50    /// Raw pixel data: `[R, G, B, R, G, B, …]`, row-major.
51    pub data: &'a [u8],
52    /// Image width in pixels.
53    pub width: u32,
54    /// Image height in pixels.
55    pub height: u32,
56}
57
58impl<'a> RgbImageView<'a> {
59    /// Construct a new view, validating that `data` is large enough.
60    pub fn new(data: &'a [u8], width: u32, height: u32) -> Result<Self> {
61        let expected = (width as usize) * (height as usize) * 3;
62        if data.len() < expected {
63            return Err(Error::InvalidData(format!(
64                "RgbImageView: buffer too small — expected {} bytes for {}×{} RGB image, got {}",
65                expected, width, height, data.len()
66            )));
67        }
68        Ok(Self { data, width, height })
69    }
70
71    /// Sample pixel color using nearest-neighbour interpolation.
72    #[inline]
73    fn sample_nearest(&self, u: f32, v: f32) -> Option<[u8; 3]> {
74        let x = u.round() as i32;
75        let y = v.round() as i32;
76        if x < 0 || y < 0 || x >= self.width as i32 || y >= self.height as i32 {
77            return None;
78        }
79        let idx = (y as usize * self.width as usize + x as usize) * 3;
80        Some([self.data[idx], self.data[idx + 1], self.data[idx + 2]])
81    }
82
83    /// Sample pixel color using bilinear interpolation.
84    #[inline]
85    fn sample_bilinear(&self, u: f32, v: f32) -> Option<[u8; 3]> {
86        let w = self.width as i32;
87        let h = self.height as i32;
88
89        let x0 = u.floor() as i32;
90        let y0 = v.floor() as i32;
91        let x1 = x0 + 1;
92        let y1 = y0 + 1;
93
94        if x0 < 0 || y0 < 0 || x1 >= w || y1 >= h {
95            // Fall back to nearest when the bilinear neighbourhood clips the border.
96            return self.sample_nearest(u, v);
97        }
98
99        let tx = u - u.floor();
100        let ty = v - v.floor();
101
102        let fetch = |x: i32, y: i32| -> [f32; 3] {
103            let idx = (y as usize * self.width as usize + x as usize) * 3;
104            [
105                self.data[idx] as f32,
106                self.data[idx + 1] as f32,
107                self.data[idx + 2] as f32,
108            ]
109        };
110
111        let c00 = fetch(x0, y0);
112        let c10 = fetch(x1, y0);
113        let c01 = fetch(x0, y1);
114        let c11 = fetch(x1, y1);
115
116        let lerp = |a: f32, b: f32, t: f32| a + (b - a) * t;
117        let r = lerp(lerp(c00[0], c10[0], tx), lerp(c01[0], c11[0], tx), ty);
118        let g = lerp(lerp(c00[1], c10[1], tx), lerp(c01[1], c11[1], tx), ty);
119        let b = lerp(lerp(c00[2], c10[2], tx), lerp(c01[2], c11[2], tx), ty);
120
121        Some([r.round() as u8, g.round() as u8, b.round() as u8])
122    }
123}
124
125/// Interpolation strategy when sampling pixel colors.
126#[derive(Debug, Clone, Copy, Default)]
127pub enum InterpolationMode {
128    /// Round projected coordinates to the nearest integer pixel.
129    NearestNeighbor,
130    /// Bilinear interpolation across the four surrounding pixels.
131    #[default]
132    Bilinear,
133}
134
135/// Configuration for [`colorize_point_cloud`].
136#[derive(Debug, Clone)]
137pub struct ColorizationConfig {
138    /// Color assigned to points that cannot be projected into any image.
139    /// Defaults to `[128, 128, 128]` (mid-grey).
140    pub default_color: [u8; 3],
141    /// Pixel interpolation method.
142    pub interpolation: InterpolationMode,
143    /// Minimum depth (in camera space, metres) for a point to be considered
144    /// visible.  Points closer than this are treated as behind the camera.
145    pub min_depth: f32,
146}
147
148impl Default for ColorizationConfig {
149    fn default() -> Self {
150        Self {
151            default_color: [128, 128, 128],
152            interpolation: InterpolationMode::default(),
153            min_depth: 1e-4,
154        }
155    }
156}
157
158/// Summary statistics returned by [`colorize_point_cloud`].
159#[derive(Debug, Clone)]
160pub struct ColorizationResult {
161    /// Colored point cloud.
162    pub cloud: PointCloud<ColoredPoint3f>,
163    /// Number of points that were successfully colored from an image.
164    pub colored_count: usize,
165    /// Number of points that received the default color (no image coverage).
166    pub uncolored_count: usize,
167}
168
169// ---------------------------------------------------------------------------
170// Core projection helpers
171// ---------------------------------------------------------------------------
172
173/// Project a single world-space point into a camera and return the image-space
174/// coordinates `(u, v)`.  Returns `None` if the point is behind the camera.
175#[inline]
176fn project_point(
177    point: &Point3f,
178    world_to_camera: &Isometry3<f32>,
179    intrinsics: &CameraIntrinsics,
180    min_depth: f32,
181) -> Option<(f32, f32)> {
182    let p_cam = world_to_camera * point;
183    let z = p_cam.z;
184    if z < min_depth {
185        return None;
186    }
187    let u = intrinsics.fx * p_cam.x / z + intrinsics.cx;
188    let v = intrinsics.fy * p_cam.y / z + intrinsics.cy;
189    Some((u, v))
190}
191
192// ---------------------------------------------------------------------------
193// Public API
194// ---------------------------------------------------------------------------
195
196/// Colorize a point cloud from a single registered RGB image.
197///
198/// # Arguments
199///
200/// * `cloud`            – Input point cloud (position only).
201/// * `image`            – Registered RGB image.
202/// * `intrinsics`       – Pinhole camera intrinsics.
203/// * `world_to_camera`  – Rigid transform that maps world-space points into
204///                        the camera coordinate frame (X right, Y down, Z forward).
205/// * `config`           – Colorization options.
206///
207/// # Returns
208///
209/// A [`ColorizationResult`] containing the colored cloud and coverage statistics.
210pub fn colorize_point_cloud(
211    cloud: &PointCloud<Point3f>,
212    image: &RgbImageView<'_>,
213    intrinsics: &CameraIntrinsics,
214    world_to_camera: &Isometry3<f32>,
215    config: &ColorizationConfig,
216) -> Result<ColorizationResult> {
217    let colored_points: Vec<(ColoredPoint3f, bool)> = cloud
218        .points
219        .par_iter()
220        .map(|point| {
221            let color = project_and_sample(point, image, intrinsics, world_to_camera, config);
222            let hit = color != config.default_color;
223            (ColoredPoint3f { position: *point, color }, hit)
224        })
225        .collect();
226
227    let colored_count = colored_points.iter().filter(|(_, hit)| *hit).count();
228    let uncolored_count = colored_points.len() - colored_count;
229    let cloud = PointCloud::from_points(colored_points.into_iter().map(|(p, _)| p).collect());
230
231    Ok(ColorizationResult { cloud, colored_count, uncolored_count })
232}
233
234/// Colorize a point cloud from multiple registered RGB images.
235///
236/// Each point is colored by the **first** image in `sources` that can see it.
237/// Supply images in decreasing priority order (most preferred camera first).
238///
239/// # Arguments
240///
241/// * `cloud`   – Input point cloud.
242/// * `sources` – Slice of `(image, intrinsics, world_to_camera)` triples.
243/// * `config`  – Colorization options.
244pub fn colorize_from_images(
245    cloud: &PointCloud<Point3f>,
246    sources: &[(RgbImageView<'_>, CameraIntrinsics, Isometry3<f32>)],
247    config: &ColorizationConfig,
248) -> Result<ColorizationResult> {
249    if sources.is_empty() {
250        return Err(Error::InvalidData(
251            "colorize_from_images: sources slice must not be empty".into(),
252        ));
253    }
254
255    let colored_points: Vec<(ColoredPoint3f, bool)> = cloud
256        .points
257        .par_iter()
258        .map(|point| {
259            for (image, intrinsics, world_to_camera) in sources {
260                let color = project_and_sample(point, image, intrinsics, world_to_camera, config);
261                if color != config.default_color {
262                    return (ColoredPoint3f { position: *point, color }, true);
263                }
264            }
265            (ColoredPoint3f { position: *point, color: config.default_color }, false)
266        })
267        .collect();
268
269    let colored_count = colored_points.iter().filter(|(_, hit)| *hit).count();
270    let uncolored_count = colored_points.len() - colored_count;
271    let cloud = PointCloud::from_points(colored_points.into_iter().map(|(p, _)| p).collect());
272
273    Ok(ColorizationResult { cloud, colored_count, uncolored_count })
274}
275
276// ---------------------------------------------------------------------------
277// Internal helper
278// ---------------------------------------------------------------------------
279
280/// Project `point` into `image` and return the sampled color, or
281/// `config.default_color` if the point is not visible.
282#[inline]
283fn project_and_sample(
284    point: &Point3f,
285    image: &RgbImageView<'_>,
286    intrinsics: &CameraIntrinsics,
287    world_to_camera: &Isometry3<f32>,
288    config: &ColorizationConfig,
289) -> [u8; 3] {
290    let Some((u, v)) = project_point(point, world_to_camera, intrinsics, config.min_depth) else {
291        return config.default_color;
292    };
293    let sampled = match config.interpolation {
294        InterpolationMode::NearestNeighbor => image.sample_nearest(u, v),
295        InterpolationMode::Bilinear => image.sample_bilinear(u, v),
296    };
297    sampled.unwrap_or(config.default_color)
298}
299
300// ---------------------------------------------------------------------------
301// Tests
302// ---------------------------------------------------------------------------
303
304#[cfg(test)]
305mod tests {
306    use super::*;
307    use nalgebra::{Isometry3, Translation3, UnitQuaternion};
308
309    /// Identity pose: camera sits at the origin looking down +Z.
310    fn identity_pose() -> Isometry3<f32> {
311        Isometry3::identity()
312    }
313
314    /// Simple 4×4 all-red image.
315    fn red_image() -> Vec<u8> {
316        vec![255u8, 0, 0].repeat(4 * 4)
317    }
318
319    fn intrinsics_4x4() -> CameraIntrinsics {
320        // For a 4×4 image, place the principal point at the centre (1.5, 1.5).
321        CameraIntrinsics { fx: 2.0, fy: 2.0, cx: 1.5, cy: 1.5 }
322    }
323
324    #[test]
325    fn test_single_point_in_view() {
326        // A point at (0,0,1) should project to the centre of a 4×4 red image.
327        let data = red_image();
328        let image = RgbImageView::new(&data, 4, 4).unwrap();
329        let intrinsics = intrinsics_4x4();
330        let pose = identity_pose();
331
332        let cloud = PointCloud::from_points(vec![Point3f::new(0.0, 0.0, 1.0)]);
333        let config = ColorizationConfig::default();
334        let result = colorize_point_cloud(&cloud, &image, &intrinsics, &pose, &config).unwrap();
335
336        assert_eq!(result.colored_count, 1);
337        assert_eq!(result.cloud.points[0].color, [255, 0, 0]);
338    }
339
340    #[test]
341    fn test_point_behind_camera() {
342        // A point at z=-1 should be invisible and receive the default color.
343        let data = red_image();
344        let image = RgbImageView::new(&data, 4, 4).unwrap();
345        let intrinsics = intrinsics_4x4();
346        let pose = identity_pose();
347
348        let cloud = PointCloud::from_points(vec![Point3f::new(0.0, 0.0, -1.0)]);
349        let config = ColorizationConfig { default_color: [0, 0, 0], ..Default::default() };
350        let result = colorize_point_cloud(&cloud, &image, &intrinsics, &pose, &config).unwrap();
351
352        assert_eq!(result.uncolored_count, 1);
353        assert_eq!(result.cloud.points[0].color, [0, 0, 0]);
354    }
355
356    #[test]
357    fn test_point_out_of_frame() {
358        // A point far to the side should project outside the 4×4 image.
359        let data = red_image();
360        let image = RgbImageView::new(&data, 4, 4).unwrap();
361        let intrinsics = intrinsics_4x4();
362        let pose = identity_pose();
363
364        let cloud = PointCloud::from_points(vec![Point3f::new(1000.0, 0.0, 1.0)]);
365        let config = ColorizationConfig { default_color: [1, 2, 3], ..Default::default() };
366        let result = colorize_point_cloud(&cloud, &image, &intrinsics, &pose, &config).unwrap();
367
368        assert_eq!(result.uncolored_count, 1);
369        assert_eq!(result.cloud.points[0].color, [1, 2, 3]);
370    }
371
372    #[test]
373    fn test_multi_image_first_wins() {
374        // Two images: red and blue.  The first (red) should win for a visible point.
375        let red = red_image();
376        let blue = vec![0u8, 0, 255].repeat(4 * 4);
377        let intrinsics = intrinsics_4x4();
378        let pose = identity_pose();
379
380        let img_red = RgbImageView::new(&red, 4, 4).unwrap();
381        let img_blue = RgbImageView::new(&blue, 4, 4).unwrap();
382
383        let cloud = PointCloud::from_points(vec![Point3f::new(0.0, 0.0, 1.0)]);
384        let config = ColorizationConfig::default();
385        let sources = vec![
386            (img_red, intrinsics, pose),
387            (img_blue, intrinsics, pose),
388        ];
389        let result = colorize_from_images(&cloud, &sources, &config).unwrap();
390        assert_eq!(result.cloud.points[0].color, [255, 0, 0]);
391    }
392
393    #[test]
394    fn test_camera_translated_along_x() {
395        // Camera moved 1 unit to the right in world space.
396        // The world-to-camera transform must account for this translation.
397        let data = red_image();
398        let image = RgbImageView::new(&data, 4, 4).unwrap();
399        let intrinsics = intrinsics_4x4();
400
401        // Camera at world position (1, 0, 0) looking down +Z.
402        // world_to_camera = inverse of camera_to_world
403        let camera_to_world = Isometry3::from_parts(
404            Translation3::new(1.0, 0.0, 0.0),
405            UnitQuaternion::identity(),
406        );
407        let world_to_camera = camera_to_world.inverse();
408
409        // A point at (1, 0, 1) is directly in front of this camera.
410        let cloud = PointCloud::from_points(vec![Point3f::new(1.0, 0.0, 1.0)]);
411        let config = ColorizationConfig::default();
412        let result =
413            colorize_point_cloud(&cloud, &image, &intrinsics, &world_to_camera, &config).unwrap();
414
415        assert_eq!(result.colored_count, 1);
416        assert_eq!(result.cloud.points[0].color, [255, 0, 0]);
417    }
418
419    #[test]
420    fn test_rgb_image_view_too_small() {
421        let result = RgbImageView::new(&[0u8; 10], 4, 4);
422        assert!(result.is_err());
423    }
424}