Skip to main content

vision_calibration_core/
lib.rs

1//! Core math and geometry primitives for `calibration-rs`.
2//!
3//! This crate provides the foundational building blocks used by all other
4//! crates in the workspace:
5//!
6//! - linear algebra type aliases (`Real`, `Vec2`, `Pt3`, and friends),
7//! - composable camera models (projection + distortion + sensor + intrinsics),
8//! - a deterministic, model-agnostic RANSAC engine.
9//!
10//! Camera pipeline (conceptually):
11//! `pixel = intrinsics(sensor(distortion(projection(dir))))`
12//!
13//! The sensor stage supports a Scheimpflug/tilted sensor homography aligned
14//! with OpenCV's `computeTiltProjectionMatrix`.
15//!
16//! # Modules
17//!
18//! - \[`math`\]: basic type aliases and homogeneous helpers.
19//! - \[`models`\]: camera model traits and configuration wrappers.
20//! - \[`ransac`\]: generic robust estimation helpers.
21//! - \[`synthetic`\]: deterministic synthetic data helpers (tests/examples/benchmarks).
22//!
23//! # Example
24//!
25//! ```no_run
26//! use vision_calibration_core::{
27//!     CameraParams, DistortionParams, FxFyCxCySkew, IntrinsicsParams, ProjectionParams,
28//!     SensorParams,
29//! };
30//!
31//! let params = CameraParams {
32//!     projection: ProjectionParams::Pinhole,
33//!     distortion: DistortionParams::None,
34//!     sensor: SensorParams::Identity,
35//!     intrinsics: IntrinsicsParams::FxFyCxCySkew {
36//!         params: FxFyCxCySkew {
37//!             fx: 800.0,
38//!             fy: 800.0,
39//!             cx: 640.0,
40//!             cy: 360.0,
41//!             skew: 0.0,
42//!         },
43//!     },
44//! };
45//! let cam = params.build();
46//! let px = cam.project_point_c(&nalgebra::Vector3::new(0.1, 0.2, 1.0));
47//! assert!(px.is_some());
48//! ```
49
50/// Typed error enum for this crate.
51pub mod error;
52/// Linear algebra type aliases and helpers.
53mod math;
54/// Camera models and distortion utilities.
55mod models;
56/// Generic RANSAC engine and traits.
57mod ransac;
58/// Deterministic synthetic data generation helpers.
59///
60/// This module provides small, reusable building blocks for constructing
61/// synthetic calibration problems (planar grids, poses, projections, noise).
62/// It is used in workspace tests/examples and can be useful for benchmarking
63/// and regression testing.
64pub mod synthetic;
65/// Test utilities for cross-crate calibration testing.
66///
67/// This module is public to allow usage in integration tests across
68/// the workspace, but is not intended for production use.
69pub mod test_utils;
70/// Common types for observations, results, and options.
71mod types;
72mod view;
73
74pub use error::Error;
75pub use math::*;
76pub use models::*;
77pub use ransac::*;
78pub use types::*;
79pub use view::*;
80
81/// Concrete pinhole camera alias used across single-camera workflows.
82///
83/// Composition:
84/// - projection: [`Pinhole`]
85/// - distortion: [`BrownConrady5`]
86/// - sensor: [`IdentitySensor`]
87/// - intrinsics: [`FxFyCxCySkew`]
88pub type PinholeCamera =
89    Camera<Real, Pinhole, BrownConrady5<Real>, IdentitySensor, FxFyCxCySkew<Real>>;
90
91/// Build a [`PinholeCamera`] from intrinsics and Brown-Conrady distortion.
92pub fn make_pinhole_camera(k: FxFyCxCySkew<Real>, dist: BrownConrady5<Real>) -> PinholeCamera {
93    Camera::new(Pinhole, dist, IdentitySensor, k)
94}
95
96/// Convert a concrete [`PinholeCamera`] into serializable [`CameraParams`].
97pub fn pinhole_camera_params(camera: &PinholeCamera) -> CameraParams {
98    CameraParams {
99        projection: ProjectionParams::Pinhole,
100        distortion: DistortionParams::BrownConrady5 {
101            params: BrownConrady5 {
102                k1: camera.dist.k1,
103                k2: camera.dist.k2,
104                k3: camera.dist.k3,
105                p1: camera.dist.p1,
106                p2: camera.dist.p2,
107                iters: camera.dist.iters,
108            },
109        },
110        sensor: SensorParams::Identity,
111        intrinsics: IntrinsicsParams::FxFyCxCySkew {
112            params: FxFyCxCySkew {
113                fx: camera.k.fx,
114                fy: camera.k.fy,
115                cx: camera.k.cx,
116                cy: camera.k.cy,
117                skew: camera.k.skew,
118            },
119        },
120    }
121}
122
123/// Metadata carrying the per-view pose `camera_se3_target`.
124pub struct TargetPose {
125    /// Pose of target frame in camera frame (`T_C_T`).
126    pub camera_se3_target: Iso3,
127}
128
129/// Compute mean per-point reprojection error for a calibrated camera and posed views.
130///
131/// The transform chain is `p_cam = T_C_T * p_target`.
132///
133/// # Errors
134///
135/// Returns [`Error::InvalidInput`] if no points could be projected.
136pub fn compute_mean_reproj_error(
137    camera: &PinholeCamera,
138    views: &[View<TargetPose>],
139) -> Result<Real, Error> {
140    let mut total_error = 0.0;
141    let mut total_points = 0;
142
143    for view in views {
144        for (p3d, p2d) in view.obs.points_3d.iter().zip(view.obs.points_2d.iter()) {
145            let p_cam = view.meta.camera_se3_target * p3d;
146            if let Some(projected) = camera.project_point_c(&p_cam.coords) {
147                let error = (projected - *p2d).norm();
148                total_error += error;
149                total_points += 1;
150            }
151        }
152    }
153
154    if total_points == 0 {
155        return Err(Error::invalid_input(
156            "no valid projections for error computation",
157        ));
158    }
159
160    Ok(total_error / total_points as Real)
161}
162
163/// Compute reprojection error statistics for a multi-camera rig dataset.
164///
165/// Uses the transform chain:
166/// - `cam_se3_target = cam_se3_rig[cam] * rig_se3_target[view]`
167/// - `p_cam = cam_se3_target * p_target`
168///
169/// where:
170/// - `cam_se3_rig[cam]` is `T_C_R` (rig -> camera)
171/// - `rig_se3_target[view]` is `T_R_T` (target -> rig)
172///
173/// Points that fail projection are skipped. Returns an error if no points are
174/// successfully projected.
175///
176/// # Errors
177///
178/// Returns [`Error::InvalidInput`] if array lengths don't match expected counts
179/// or if no points could be projected.
180pub fn compute_rig_reprojection_stats<Meta>(
181    cameras: &[PinholeCamera],
182    dataset: &RigDataset<Meta>,
183    cam_se3_rig: &[Iso3],
184    rig_se3_target: &[Iso3],
185) -> Result<ReprojectionStats, Error> {
186    if cameras.len() != dataset.num_cameras {
187        return Err(Error::invalid_input(format!(
188            "camera count {} != num_cameras {}",
189            cameras.len(),
190            dataset.num_cameras
191        )));
192    }
193    if cam_se3_rig.len() != dataset.num_cameras {
194        return Err(Error::invalid_input(format!(
195            "cam_se3_rig count {} != num_cameras {}",
196            cam_se3_rig.len(),
197            dataset.num_cameras
198        )));
199    }
200    if rig_se3_target.len() != dataset.num_views() {
201        return Err(Error::invalid_input(format!(
202            "rig_se3_target count {} != num_views {}",
203            rig_se3_target.len(),
204            dataset.num_views()
205        )));
206    }
207
208    let mut sum = 0.0_f64;
209    let mut sum_sq = 0.0_f64;
210    let mut max = 0.0_f64;
211    let mut count = 0usize;
212
213    for (view_idx, view) in dataset.views.iter().enumerate() {
214        for (cam_idx, cam_obs) in view.obs.cameras.iter().enumerate() {
215            let Some(obs) = cam_obs else {
216                continue;
217            };
218            let cam = &cameras[cam_idx];
219            let cam_se3_target = cam_se3_rig[cam_idx] * rig_se3_target[view_idx];
220
221            for (pw, uv) in obs.points_3d.iter().zip(obs.points_2d.iter()) {
222                let p_cam = cam_se3_target * pw;
223                let Some(proj) = cam.project_point_c(&p_cam.coords) else {
224                    continue;
225                };
226                let err = (proj - *uv).norm();
227                sum += err;
228                sum_sq += err * err;
229                max = max.max(err);
230                count += 1;
231            }
232        }
233    }
234
235    if count == 0 {
236        return Err(Error::invalid_input(
237            "no valid projections for error computation",
238        ));
239    }
240
241    let count_f = count as f64;
242    Ok(ReprojectionStats {
243        mean: sum / count_f,
244        rms: (sum_sq / count_f).sqrt(),
245        max,
246        count,
247    })
248}
249
250/// Compute per-camera reprojection error statistics for a multi-camera rig dataset.
251///
252/// Uses the same transform chain as [`compute_rig_reprojection_stats`], but splits
253/// the aggregation by camera index.
254///
255/// # Errors
256///
257/// Returns [`Error::InvalidInput`] if array lengths don't match expected counts
258/// or if any camera has no valid projections.
259pub fn compute_rig_reprojection_stats_per_camera<Meta>(
260    cameras: &[PinholeCamera],
261    dataset: &RigDataset<Meta>,
262    cam_se3_rig: &[Iso3],
263    rig_se3_target: &[Iso3],
264) -> Result<Vec<ReprojectionStats>, Error> {
265    if cameras.len() != dataset.num_cameras {
266        return Err(Error::invalid_input(format!(
267            "camera count {} != num_cameras {}",
268            cameras.len(),
269            dataset.num_cameras
270        )));
271    }
272    if cam_se3_rig.len() != dataset.num_cameras {
273        return Err(Error::invalid_input(format!(
274            "cam_se3_rig count {} != num_cameras {}",
275            cam_se3_rig.len(),
276            dataset.num_cameras
277        )));
278    }
279    if rig_se3_target.len() != dataset.num_views() {
280        return Err(Error::invalid_input(format!(
281            "rig_se3_target count {} != num_views {}",
282            rig_se3_target.len(),
283            dataset.num_views()
284        )));
285    }
286
287    let mut sum = vec![0.0_f64; dataset.num_cameras];
288    let mut sum_sq = vec![0.0_f64; dataset.num_cameras];
289    let mut max = vec![0.0_f64; dataset.num_cameras];
290    let mut count = vec![0usize; dataset.num_cameras];
291
292    for (view_idx, view) in dataset.views.iter().enumerate() {
293        for (cam_idx, cam_obs) in view.obs.cameras.iter().enumerate() {
294            let Some(obs) = cam_obs else {
295                continue;
296            };
297            let cam = &cameras[cam_idx];
298            let cam_se3_target = cam_se3_rig[cam_idx] * rig_se3_target[view_idx];
299
300            for (pw, uv) in obs.points_3d.iter().zip(obs.points_2d.iter()) {
301                let p_cam = cam_se3_target * pw;
302                let Some(proj) = cam.project_point_c(&p_cam.coords) else {
303                    continue;
304                };
305                let err = (proj - *uv).norm();
306                sum[cam_idx] += err;
307                sum_sq[cam_idx] += err * err;
308                max[cam_idx] = max[cam_idx].max(err);
309                count[cam_idx] += 1;
310            }
311        }
312    }
313
314    let mut stats = Vec::with_capacity(dataset.num_cameras);
315    for cam_idx in 0..dataset.num_cameras {
316        if count[cam_idx] == 0 {
317            return Err(Error::invalid_input(format!(
318                "camera {cam_idx} has no valid projections for error computation"
319            )));
320        }
321        let n = count[cam_idx] as f64;
322        stats.push(ReprojectionStats {
323            mean: sum[cam_idx] / n,
324            rms: (sum_sq[cam_idx] / n).sqrt(),
325            max: max[cam_idx],
326            count: count[cam_idx],
327        });
328    }
329    Ok(stats)
330}
331
332#[cfg(test)]
333mod tests {
334    use super::*;
335    use nalgebra::{Rotation3, Translation3};
336
337    fn make_iso(angles: (Real, Real, Real), t: (Real, Real, Real)) -> Iso3 {
338        let rot = Rotation3::from_euler_angles(angles.0, angles.1, angles.2);
339        let tr = Translation3::new(t.0, t.1, t.2);
340        Iso3::from_parts(tr, rot.into())
341    }
342
343    #[test]
344    fn rig_reprojection_stats_zero_for_perfect_data() -> anyhow::Result<()> {
345        let cam0 = make_pinhole_camera(
346            FxFyCxCySkew {
347                fx: 800.0,
348                fy: 800.0,
349                cx: 320.0,
350                cy: 240.0,
351                skew: 0.0,
352            },
353            BrownConrady5::default(),
354        );
355        let cam1 = cam0.clone();
356
357        let cam_se3_rig = vec![Iso3::identity(), make_iso((0.0, 0.0, 0.0), (0.2, 0.0, 0.0))];
358        let rig_se3_target = vec![make_iso((0.0, 0.0, 0.0), (0.0, 0.0, 1.0))];
359
360        let points_3d = vec![
361            Pt3::new(0.0, 0.0, 0.0),
362            Pt3::new(0.1, 0.0, 0.0),
363            Pt3::new(0.0, 0.1, 0.0),
364            Pt3::new(0.1, 0.1, 0.0),
365        ];
366
367        let make_obs =
368            |cam: &PinholeCamera, cam_se3_target: &Iso3| -> anyhow::Result<CorrespondenceView> {
369                let points_2d = points_3d
370                    .iter()
371                    .map(|p| {
372                        let p_cam = cam_se3_target * p;
373                        cam.project_point_c(&p_cam.coords)
374                            .ok_or_else(|| anyhow::anyhow!("projection failed"))
375                    })
376                    .collect::<anyhow::Result<Vec<_>>>()?;
377                CorrespondenceView::new(points_3d.clone(), points_2d)
378                    .map_err(|e| anyhow::anyhow!("{e}"))
379            };
380
381        let view = RigView {
382            meta: NoMeta,
383            obs: RigViewObs {
384                cameras: vec![
385                    Some(make_obs(&cam0, &(cam_se3_rig[0] * rig_se3_target[0]))?),
386                    Some(make_obs(&cam1, &(cam_se3_rig[1] * rig_se3_target[0]))?),
387                ],
388            },
389        };
390        let dataset = RigDataset::new(vec![view], 2)?;
391
392        let cameras = [cam0, cam1];
393        let stats =
394            compute_rig_reprojection_stats(&cameras, &dataset, &cam_se3_rig, &rig_se3_target)?;
395        assert_eq!(stats.count, 8);
396        assert!(stats.mean < 1e-12, "mean {}", stats.mean);
397        assert!(stats.rms < 1e-12, "rms {}", stats.rms);
398        assert!(stats.max < 1e-12, "max {}", stats.max);
399
400        let per_cam = compute_rig_reprojection_stats_per_camera(
401            &cameras,
402            &dataset,
403            &cam_se3_rig,
404            &rig_se3_target,
405        )?;
406        assert_eq!(per_cam.len(), 2);
407        assert_eq!(per_cam[0].count, 4);
408        assert_eq!(per_cam[1].count, 4);
409        assert!(per_cam[0].mean < 1e-12, "cam0 mean {}", per_cam[0].mean);
410        assert!(per_cam[1].mean < 1e-12, "cam1 mean {}", per_cam[1].mean);
411
412        Ok(())
413    }
414}