Skip to main content

apex_camera_models/
lib.rs

1//! Camera projection models for computer vision applications.
2//!
3//! This crate provides a comprehensive collection of camera projection models commonly used in
4//! bundle adjustment, SLAM, visual odometry, and Structure-from-Motion (SfM). All models implement
5//! the [`CameraModel`] trait providing a unified interface for projection, unprojection, and
6//! analytic Jacobian computation.
7//!
8//! # Core Architecture
9//!
10//! ## CameraModel Trait
11//!
12//! The [`CameraModel`] trait defines the interface that all camera models must implement:
13//!
14//! - **Projection**: 3D point (x,y,z) → 2D pixel (u,v)
15//! - **Unprojection**: 2D pixel (u,v) → 3D unit ray
16//! - **Jacobians**: Analytic derivatives for optimization
17//!   - Point Jacobian: ∂(u,v)/∂(x,y,z) — 2×3 matrix
18//!   - Pose Jacobian: ∂(u,v)/∂(pose) — 2×6 matrix (SE3 tangent space)
19//!   - Intrinsic Jacobian: ∂(u,v)/∂(params) — 2×N matrix (N = parameter count)
20//!
21//! ## Error Handling
22//!
23//! All operations return [`Result`] with [`CameraModelError`] providing structured error variants
24//! that include actual parameter values for debugging:
25//!
26//! - Parameter validation: `FocalLengthNotPositive`, `FocalLengthNotFinite`, `ParameterOutOfRange`
27//! - Projection errors: `PointBehindCamera`, `ProjectionOutOfBounds`, `DenominatorTooSmall`
28//! - Numerical errors: `NumericalError` with operation context
29//!
30//! # Available Camera Models
31//!
32//! ## Standard Models (FOV < 90°)
33//! - **Pinhole**: Standard perspective projection (4 params: fx, fy, cx, cy)
34//! - **Radial-Tangential**: OpenCV Brown-Conrady model (9 params with k1,k2,k3,p1,p2)
35//!
36//! ## Wide-Angle Models (FOV 90°-180°)
37//! - **Kannala-Brandt**: Polynomial fisheye model (8 params, θ-based distortion)
38//! - **FOV**: Field-of-view model (5 params, atan-based)
39//!
40//! ## Omnidirectional Models (FOV > 180°)
41//! - **UCM**: Unified Camera Model (5 params, α parameter)
42//! - **EUCM**: Extended Unified Camera Model (6 params, α, β parameters)
43//! - **Double Sphere**: Two-sphere projection (6 params, ξ, α parameters)
44//!
45//! ## Specialized Models
46//! - **BAL Pinhole**: Bundle Adjustment in the Large format (6 params, -Z convention)
47
48use apex_manifolds::LieGroup;
49use apex_manifolds::se3::SE3;
50use nalgebra::{Matrix2xX, Matrix3, Matrix3xX, SMatrix, Vector2, Vector3};
51
52/// Precision constant for geometric validity checks (e.g., point in front of camera).
53///
54/// Used to determine if a 3D point is geometrically valid for projection.
55/// Default: 1e-6 (micrometers at meter scale)
56pub const GEOMETRIC_PRECISION: f64 = 1e-6;
57
58/// Epsilon for numerical differentiation in Jacobian computation.
59///
60/// Used when computing numerical derivatives for validation and testing.
61/// Default: 1e-7 (provides good balance between truncation and round-off error)
62pub const NUMERICAL_DERIVATIVE_EPS: f64 = 1e-7;
63
64/// Tolerance for numerical Jacobian validation in tests.
65///
66/// Maximum allowed difference between analytical and numerical Jacobians.
67/// Default: 1e-5 (allows for small numerical errors in finite differences)
68pub const JACOBIAN_TEST_TOLERANCE: f64 = 1e-5;
69
70/// Tolerance for projection/unprojection test assertions.
71///
72/// Maximum allowed error in pixel coordinates for test assertions.
73/// Default: 1e-10 (essentially exact for double precision)
74pub const PROJECTION_TEST_TOLERANCE: f64 = 1e-10;
75
76/// Minimum depth for valid 3D points (meters).
77///
78/// Points closer than this to the camera are considered invalid.
79/// Default: 1e-6 meters (1 micrometer)
80pub const MIN_DEPTH: f64 = 1e-6;
81
82/// Convergence threshold for iterative unprojection algorithms.
83///
84/// Used in camera models that require iterative solving (e.g., Kannala-Brandt).
85/// Default: 1e-6
86pub const CONVERGENCE_THRESHOLD: f64 = 1e-6;
87
88/// Camera model errors.
89#[derive(thiserror::Error, Debug)]
90pub enum CameraModelError {
91    /// Focal length must be positive: fx={fx}, fy={fy}
92    #[error("Focal length must be positive: fx={fx}, fy={fy}")]
93    FocalLengthNotPositive { fx: f64, fy: f64 },
94
95    /// Focal length must be finite: fx={fx}, fy={fy}
96    #[error("Focal length must be finite: fx={fx}, fy={fy}")]
97    FocalLengthNotFinite { fx: f64, fy: f64 },
98
99    /// Principal point must be finite: cx={cx}, cy={cy}
100    #[error("Principal point must be finite: cx={cx}, cy={cy}")]
101    PrincipalPointNotFinite { cx: f64, cy: f64 },
102
103    /// Distortion coefficient must be finite
104    #[error("Distortion coefficient '{name}' must be finite, got {value}")]
105    DistortionNotFinite { name: String, value: f64 },
106
107    /// Parameter out of range
108    #[error("Parameter '{param}' must be in range [{min}, {max}], got {value}")]
109    ParameterOutOfRange {
110        param: String,
111        value: f64,
112        min: f64,
113        max: f64,
114    },
115
116    /// Point behind camera
117    #[error("Point behind camera: z={z} (must be > {min_z})")]
118    PointBehindCamera { z: f64, min_z: f64 },
119
120    /// Point at camera center
121    #[error("Point at camera center: 3D point too close to optical axis")]
122    PointAtCameraCenter,
123
124    /// Projection denominator too small
125    #[error("Projection denominator too small: denom={denom} (threshold={threshold})")]
126    DenominatorTooSmall { denom: f64, threshold: f64 },
127
128    /// Projection outside valid image region
129    #[error("Projection outside valid image region")]
130    ProjectionOutOfBounds,
131
132    /// Point outside image bounds
133    #[error("Point outside image bounds: ({x}, {y}) not in valid region")]
134    PointOutsideImage { x: f64, y: f64 },
135
136    /// Numerical error
137    #[error("Numerical error in {operation}: {details}")]
138    NumericalError { operation: String, details: String },
139
140    /// Generic invalid parameters
141    #[error("Invalid camera parameters: {0}")]
142    InvalidParams(String),
143}
144
145/// The "Common 4" - Linear intrinsic parameters.
146///
147/// These define the projection matrix K for the pinhole camera model.
148#[derive(Debug, Clone, Copy, PartialEq)]
149pub struct PinholeParams {
150    /// Focal length in x direction (pixels)
151    pub fx: f64,
152    /// Focal length in y direction (pixels)
153    pub fy: f64,
154    /// Principal point x-coordinate (pixels)
155    pub cx: f64,
156    /// Principal point y-coordinate (pixels)
157    pub cy: f64,
158}
159
160impl PinholeParams {
161    /// Create new pinhole parameters with validation.
162    pub fn new(fx: f64, fy: f64, cx: f64, cy: f64) -> Result<Self, CameraModelError> {
163        let params = Self { fx, fy, cx, cy };
164        params.validate()?;
165        Ok(params)
166    }
167
168    /// Validate pinhole parameters.
169    pub fn validate(&self) -> Result<(), CameraModelError> {
170        if self.fx <= 0.0 || self.fy <= 0.0 {
171            return Err(CameraModelError::FocalLengthNotPositive {
172                fx: self.fx,
173                fy: self.fy,
174            });
175        }
176        if !self.fx.is_finite() || !self.fy.is_finite() {
177            return Err(CameraModelError::FocalLengthNotFinite {
178                fx: self.fx,
179                fy: self.fy,
180            });
181        }
182        if !self.cx.is_finite() || !self.cy.is_finite() {
183            return Err(CameraModelError::PrincipalPointNotFinite {
184                cx: self.cx,
185                cy: self.cy,
186            });
187        }
188        Ok(())
189    }
190}
191
192/// Lens distortion models.
193///
194/// This enum captures all supported distortion models with their parameters.
195#[derive(Debug, Clone, Copy, PartialEq)]
196pub enum DistortionModel {
197    /// Perfect pinhole (no distortion)
198    None,
199
200    /// BAL-style radial distortion (2 parameters: k1, k2)
201    ///
202    /// Used in Bundle Adjustment in the Large datasets.
203    Radial { k1: f64, k2: f64 },
204
205    /// Brown-Conrady / OpenCV model (5 parameters)
206    ///
207    /// Standard model used in OpenCV: k1, k2, k3 (radial), p1, p2 (tangential)
208    BrownConrady {
209        k1: f64,
210        k2: f64,
211        p1: f64,
212        p2: f64,
213        k3: f64,
214    },
215
216    /// Kannala-Brandt fisheye model (4 parameters)
217    ///
218    /// Polynomial distortion model for fisheye lenses.
219    KannalaBrandt { k1: f64, k2: f64, k3: f64, k4: f64 },
220
221    /// Field-of-View model (1 parameter)
222    ///
223    /// Single-parameter fisheye model based on field of view.
224    FOV { w: f64 },
225
226    /// Unified Camera Model (1 parameter)
227    ///
228    /// Single-viewpoint catadioptric camera model.
229    UCM { alpha: f64 },
230
231    /// Extended Unified Camera Model (2 parameters)
232    ///
233    /// Extension of UCM with improved accuracy.
234    EUCM { alpha: f64, beta: f64 },
235
236    /// Double Sphere model (2 parameters)
237    ///
238    /// Two-parameter fisheye model with improved wide-angle accuracy.
239    DoubleSphere { xi: f64, alpha: f64 },
240}
241
242fn check_finite(name: &str, value: f64) -> Result<(), CameraModelError> {
243    if !value.is_finite() {
244        return Err(CameraModelError::DistortionNotFinite {
245            name: name.to_string(),
246            value,
247        });
248    }
249    Ok(())
250}
251
252impl DistortionModel {
253    /// Validate distortion parameters for the given model variant.
254    pub fn validate(&self) -> Result<(), CameraModelError> {
255        match self {
256            DistortionModel::None => Ok(()),
257            DistortionModel::Radial { k1, k2 } => {
258                check_finite("k1", *k1)?;
259                check_finite("k2", *k2)
260            }
261            DistortionModel::BrownConrady { k1, k2, p1, p2, k3 } => {
262                check_finite("k1", *k1)?;
263                check_finite("k2", *k2)?;
264                check_finite("p1", *p1)?;
265                check_finite("p2", *p2)?;
266                check_finite("k3", *k3)
267            }
268            DistortionModel::KannalaBrandt { k1, k2, k3, k4 } => {
269                check_finite("k1", *k1)?;
270                check_finite("k2", *k2)?;
271                check_finite("k3", *k3)?;
272                check_finite("k4", *k4)
273            }
274            DistortionModel::FOV { w } => {
275                if !w.is_finite() || *w <= 0.0 || *w > std::f64::consts::PI {
276                    return Err(CameraModelError::ParameterOutOfRange {
277                        param: "w".to_string(),
278                        value: *w,
279                        min: 0.0,
280                        max: std::f64::consts::PI,
281                    });
282                }
283                Ok(())
284            }
285            DistortionModel::UCM { alpha } => {
286                if !alpha.is_finite() || !(0.0..=1.0).contains(alpha) {
287                    return Err(CameraModelError::ParameterOutOfRange {
288                        param: "alpha".to_string(),
289                        value: *alpha,
290                        min: 0.0,
291                        max: 1.0,
292                    });
293                }
294                Ok(())
295            }
296            DistortionModel::EUCM { alpha, beta } => {
297                if !alpha.is_finite() || !(0.0..=1.0).contains(alpha) {
298                    return Err(CameraModelError::ParameterOutOfRange {
299                        param: "alpha".to_string(),
300                        value: *alpha,
301                        min: 0.0,
302                        max: 1.0,
303                    });
304                }
305                if !beta.is_finite() || *beta <= 0.0 {
306                    return Err(CameraModelError::ParameterOutOfRange {
307                        param: "beta".to_string(),
308                        value: *beta,
309                        min: 0.0,
310                        max: f64::INFINITY,
311                    });
312                }
313                Ok(())
314            }
315            DistortionModel::DoubleSphere { xi, alpha } => {
316                if !xi.is_finite() || !(-1.0..=1.0).contains(xi) {
317                    return Err(CameraModelError::ParameterOutOfRange {
318                        param: "xi".to_string(),
319                        value: *xi,
320                        min: -1.0,
321                        max: 1.0,
322                    });
323                }
324                if !alpha.is_finite() || *alpha <= 0.0 || *alpha > 1.0 {
325                    return Err(CameraModelError::ParameterOutOfRange {
326                        param: "alpha".to_string(),
327                        value: *alpha,
328                        min: 0.0,
329                        max: 1.0,
330                    });
331                }
332                Ok(())
333            }
334        }
335    }
336}
337
338/// Validates that a 3D point is in front of the camera.
339///
340/// A point must have positive z-coordinate (in camera frame) to be valid for projection.
341/// Points too close to the camera center (z ≈ 0) are rejected to avoid numerical instability.
342///
343/// # Arguments
344///
345/// * `z` - Z-coordinate of the point in camera frame (meters)
346///
347/// # Returns
348///
349/// - `Ok(())` if z > √ε (approximately 1.5e-8)
350/// - `Err(CameraModelError::PointAtCameraCenter)` if z is too small
351///
352/// # Mathematical Condition
353///
354/// The validation ensures the point is geometrically in front of the camera:
355/// ```text
356/// z > √ε ≈ 1.49 × 10^-8
357/// ```
358/// where ε is machine epsilon for f64 (≈ 2.22 × 10^-16).
359pub fn validate_point_in_front(z: f64) -> Result<(), CameraModelError> {
360    if z < f64::EPSILON.sqrt() {
361        return Err(CameraModelError::PointAtCameraCenter);
362    }
363    Ok(())
364}
365
366// Camera model modules
367
368pub mod bal_pinhole;
369pub mod double_sphere;
370pub mod eucm;
371pub mod fov;
372pub mod kannala_brandt;
373pub mod pinhole;
374pub mod rad_tan;
375pub mod ucm;
376
377// Re-export camera types
378pub use bal_pinhole::BALPinholeCameraStrict;
379pub use double_sphere::DoubleSphereCamera;
380pub use eucm::EucmCamera;
381pub use fov::FovCamera;
382pub use kannala_brandt::KannalaBrandtCamera;
383pub use pinhole::PinholeCamera;
384pub use rad_tan::RadTanCamera;
385pub use ucm::UcmCamera;
386
387// Camera Model Trait
388
389/// Trait for camera projection models.
390///
391/// Defines the interface for camera models used in bundle adjustment and SfM.
392///
393/// # Type Parameters
394///
395/// - `INTRINSIC_DIM`: Number of intrinsic parameters
396/// - `IntrinsicJacobian`: Jacobian type for intrinsics (2 × INTRINSIC_DIM)
397/// - `PointJacobian`: Jacobian type for 3D point (2 × 3)
398pub trait CameraModel: Send + Sync + Clone + std::fmt::Debug + 'static {
399    /// Number of intrinsic parameters (compile-time constant).
400    const INTRINSIC_DIM: usize;
401
402    /// Jacobian type for intrinsics: 2 × INTRINSIC_DIM.
403    type IntrinsicJacobian: Clone
404        + std::fmt::Debug
405        + Default
406        + std::ops::Index<(usize, usize), Output = f64>;
407
408    /// Jacobian type for 3D point: 2 × 3.
409    type PointJacobian: Clone
410        + std::fmt::Debug
411        + Default
412        + std::ops::Mul<SMatrix<f64, 3, 6>, Output = SMatrix<f64, 2, 6>>
413        + std::ops::Mul<Matrix3<f64>, Output = SMatrix<f64, 2, 3>>
414        + std::ops::Index<(usize, usize), Output = f64>;
415
416    /// Projects a 3D point in camera coordinates to 2D image coordinates.
417    ///
418    /// The projection pipeline is: 3D point → normalized coordinates → distortion → pixel coordinates.
419    ///
420    /// # Mathematical Formula
421    ///
422    /// For a 3D point p = (x, y, z) in camera frame:
423    /// ```text
424    /// (u, v) = K · distort(x/z, y/z)
425    /// ```
426    /// where K is the intrinsic matrix [fx 0 cx; 0 fy cy; 0 0 1].
427    ///
428    /// # Arguments
429    ///
430    /// * `p_cam` - 3D point in camera coordinate frame (x, y, z) in meters
431    ///
432    /// # Returns
433    ///
434    /// - `Ok(Vector2)` - 2D image coordinates (u, v) in pixels if projection is valid
435    /// - `Err(CameraModelError)` - If point is behind camera, at center, or causes numerical issues
436    ///
437    /// # Errors
438    ///
439    /// - `PointBehindCamera` - If z ≤ GEOMETRIC_PRECISION (point behind or too close)
440    /// - `PointAtCameraCenter` - If point is too close to optical axis
441    /// - `DenominatorTooSmall` - If projection causes numerical instability
442    /// - `ProjectionOutOfBounds` - If projection falls outside valid image region
443    fn project(&self, p_cam: &Vector3<f64>) -> Result<Vector2<f64>, CameraModelError>;
444
445    /// Unprojects a 2D image point to a normalized 3D ray in camera frame.
446    ///
447    /// The inverse of projection: 2D pixel → undistortion → normalized 3D ray.
448    /// Some models use iterative methods (e.g., Newton-Raphson) for undistortion.
449    ///
450    /// # Mathematical Formula
451    ///
452    /// For a 2D point (u, v) in image coordinates:
453    /// ```text
454    /// (mx, my) = ((u - cx)/fx, (v - cy)/fy)
455    /// ray = normalize(undistort(mx, my))
456    /// ```
457    ///
458    /// # Arguments
459    ///
460    /// * `point_2d` - 2D point in image coordinates (u, v) in pixels
461    ///
462    /// # Returns
463    ///
464    /// - `Ok(Vector3)` - Normalized 3D ray direction (unit vector)
465    /// - `Err(CameraModelError)` - If point is outside valid image region or numerical issues occur
466    ///
467    /// # Errors
468    ///
469    /// - `PointOutsideImage` - If 2D point is outside valid unprojection region
470    /// - `NumericalError` - If iterative solver fails to converge
471    fn unproject(&self, point_2d: &Vector2<f64>) -> Result<Vector3<f64>, CameraModelError>;
472
473    /// Jacobian of projection with respect to 3D point coordinates.
474    ///
475    /// Returns the 2×3 matrix J where J[i,j] = ∂(u,v)[i] / ∂(x,y,z)[j].
476    ///
477    /// # Mathematical Formula
478    ///
479    /// ```text
480    /// J = ∂(u,v)/∂(x,y,z) = [ ∂u/∂x  ∂u/∂y  ∂u/∂z ]
481    ///                       [ ∂v/∂x  ∂v/∂y  ∂v/∂z ]
482    /// ```
483    ///
484    /// This Jacobian is used for:
485    /// - Structure optimization (adjusting 3D landmark positions)
486    /// - Triangulation refinement
487    /// - Bundle adjustment with landmark optimization
488    ///
489    /// # Arguments
490    ///
491    /// * `p_cam` - 3D point in camera coordinate frame (x, y, z) in meters
492    ///
493    /// # Returns
494    ///
495    /// 2×3 Jacobian matrix of projection w.r.t. point coordinates
496    fn jacobian_point(&self, p_cam: &Vector3<f64>) -> Self::PointJacobian;
497
498    /// Jacobian of projection w.r.t. camera pose (SE3).
499    ///
500    /// # Mathematical Derivation
501    ///
502    /// The pose is treated as a **world-to-camera** transform T_wc so that:
503    ///
504    /// ```text
505    /// p_cam = T_wc · p_world = R · p_world + t
506    /// ```
507    ///
508    /// ## Perturbation Model (Right Jacobian)
509    ///
510    /// We perturb the pose with a right perturbation:
511    ///
512    /// ```text
513    /// T'(δξ) = T · Exp(δξ),  δξ = [δρ; δθ] ∈ ℝ⁶
514    /// ```
515    ///
516    /// The perturbed camera-frame point becomes:
517    ///
518    /// ```text
519    /// p_cam' = R·(I + [δθ]×)·p_world + (t + R·δρ)
520    ///        = p_cam + R·δρ - R·[p_world]×·δθ
521    /// ```
522    ///
523    /// Taking derivatives:
524    ///
525    /// ```text
526    /// ∂p_cam/∂δρ = R
527    /// ∂p_cam/∂δθ = -R · [p_world]×
528    /// ```
529    ///
530    /// ## Return Value
531    ///
532    /// Returns a tuple `(J_pixel_point, J_point_pose)`:
533    /// - `J_pixel_point`: 2×3 Jacobian ∂uv/∂p_cam (from jacobian_point)
534    /// - `J_point_pose`: 3×6 Jacobian ∂p_cam/∂δξ = [R | -R·[p_world]×]
535    ///
536    /// The caller multiplies these to get the full 2×6 Jacobian ∂uv/∂δξ.
537    ///
538    /// ## SE(3) Conventions
539    ///
540    /// - **Pose meaning**: world-to-camera T_wc (p_cam = R·p_world + t)
541    /// - **Parameterization**: δξ = [δρ_x, δρ_y, δρ_z, δθ_x, δθ_y, δθ_z]
542    /// - **Perturbation**: Right perturbation T' = T · Exp(δξ)
543    /// - **Result**: ∂p_cam/∂δρ = R, ∂p_cam/∂δθ = -R·[p_world]×
544    fn jacobian_pose(
545        &self,
546        p_world: &Vector3<f64>,
547        pose: &SE3,
548    ) -> (Self::PointJacobian, SMatrix<f64, 3, 6>) {
549        // Transform world point to camera frame (world-to-camera convention)
550        let p_cam = pose.act(p_world, None, None);
551
552        // 2×3 projection Jacobian ∂(u,v)/∂(p_cam)
553        let d_uv_d_pcam = self.jacobian_point(&p_cam);
554
555        // 3×6 transformation Jacobian ∂(p_cam)/∂(pose) for right perturbation on T_wc:
556        //   ∂p_cam/∂δρ = R        (cols 0-2)
557        //   ∂p_cam/∂δθ = -R·[p_world]×  (cols 3-5)
558        let rotation = pose.rotation_so3().rotation_matrix();
559        let p_world_skew = skew_symmetric(p_world);
560
561        let d_pcam_d_pose = SMatrix::<f64, 3, 6>::from_fn(|r, c| {
562            if c < 3 {
563                rotation[(r, c)]
564            } else {
565                let col = c - 3;
566                -(0..3)
567                    .map(|k| rotation[(r, k)] * p_world_skew[(k, col)])
568                    .sum::<f64>()
569            }
570        });
571
572        (d_uv_d_pcam, d_pcam_d_pose)
573    }
574
575    /// Jacobian of projection with respect to intrinsic parameters.
576    ///
577    /// Returns the 2×N matrix where N = INTRINSIC_DIM (model-dependent).
578    ///
579    /// # Mathematical Formula
580    ///
581    /// ```text
582    /// J = ∂(u,v)/∂(params) = [ ∂u/∂fx  ∂u/∂fy  ∂u/∂cx  ∂u/∂cy  ∂u/∂k1  ... ]
583    ///                       [ ∂v/∂fx  ∂v/∂fy  ∂v/∂cx  ∂v/∂cy  ∂v/∂k1  ... ]
584    /// ```
585    ///
586    /// Intrinsic parameters vary by model:
587    /// - Pinhole: [fx, fy, cx, cy] (4 params)
588    /// - RadTan: [fx, fy, cx, cy, k1, k2, p1, p2, k3] (9 params)
589    /// - Kannala-Brandt: [fx, fy, cx, cy, k1, k2, k3, k4] (8 params)
590    ///
591    /// # Arguments
592    ///
593    /// * `p_cam` - 3D point in camera coordinate frame (x, y, z) in meters
594    ///
595    /// # Returns
596    ///
597    /// 2×N Jacobian matrix of projection w.r.t. intrinsic parameters
598    ///
599    /// # Usage
600    ///
601    /// Used in camera calibration and self-calibration bundle adjustment.
602    fn jacobian_intrinsics(&self, p_cam: &Vector3<f64>) -> Self::IntrinsicJacobian;
603
604    /// Batch projection of multiple 3D points to 2D image coordinates.
605    ///
606    /// Projects N 3D points efficiently. Invalid projections are marked with a sentinel
607    /// value (1e6, 1e6) rather than returning an error.
608    ///
609    /// # Arguments
610    ///
611    /// * `points_cam` - 3×N matrix where each column is a 3D point (x, y, z) in camera frame
612    ///
613    /// # Returns
614    ///
615    /// 2×N matrix where each column is the projected 2D point (u, v) in pixels.
616    /// Invalid projections are set to (1e6, 1e6).
617    ///
618    /// # Performance
619    ///
620    /// Default implementation iterates over points. Camera models may override
621    /// with vectorized implementations for better performance.
622    fn project_batch(&self, points_cam: &Matrix3xX<f64>) -> Matrix2xX<f64> {
623        let n = points_cam.ncols();
624        let mut result = Matrix2xX::zeros(n);
625        for i in 0..n {
626            let p = Vector3::new(points_cam[(0, i)], points_cam[(1, i)], points_cam[(2, i)]);
627            match self.project(&p) {
628                Ok(uv) => result.set_column(i, &uv),
629                Err(_) => result.set_column(i, &Vector2::new(1e6, 1e6)),
630            }
631        }
632        result
633    }
634
635    /// Validates camera intrinsic and distortion parameters.
636    ///
637    /// Performs comprehensive validation including:
638    /// - Focal lengths: must be positive and finite
639    /// - Principal point: must be finite
640    /// - Distortion coefficients: must be finite
641    /// - Model-specific constraints (e.g., UCM α ∈ [0,1], Double Sphere ξ ∈ [-1,1])
642    ///
643    /// # Validation Rules
644    ///
645    /// Common validations across all models:
646    /// - `fx > 0`, `fy > 0` (focal lengths must be positive)
647    /// - `fx`, `fy` finite (no NaN or Inf)
648    /// - `cx`, `cy` finite (principal point must be valid)
649    ///
650    /// Model-specific validations:
651    /// - **UCM**: α ∈ [0, 1]
652    /// - **EUCM**: α ∈ [0, 1], β > 0
653    /// - **Double Sphere**: ξ ∈ [-1, 1], α ∈ (0, 1]
654    /// - **FOV**: w ∈ (0, π]
655    ///
656    /// # Returns
657    ///
658    /// - `Ok(())` - All parameters satisfy validation rules
659    /// - `Err(CameraModelError)` - Specific error indicating which parameter is invalid
660    fn validate_params(&self) -> Result<(), CameraModelError>;
661
662    /// Returns the pinhole parameters (fx, fy, cx, cy).
663    ///
664    /// # Returns
665    ///
666    /// [`PinholeParams`] struct containing focal lengths and principal point.
667    fn get_pinhole_params(&self) -> PinholeParams;
668
669    /// Returns the distortion model and parameters.
670    ///
671    /// # Returns
672    ///
673    /// [`DistortionModel`] enum variant with model-specific parameters.
674    /// Returns `DistortionModel::None` for pinhole cameras without distortion.
675    fn get_distortion(&self) -> DistortionModel;
676
677    /// Returns the camera model name identifier.
678    ///
679    /// # Returns
680    ///
681    /// Static string identifier for the camera model type:
682    /// - `"pinhole"`, `"rad_tan"`, `"kannala_brandt"`, etc.
683    fn get_model_name(&self) -> &'static str;
684}
685
686/// Compute skew-symmetric matrix from a 3D vector.
687///
688/// Returns the cross-product matrix [v]× such that [v]× w = v × w.
689///
690/// # Mathematical Form
691///
692/// ```text
693/// [  0  -vz   vy ]
694/// [ vz    0  -vx ]
695/// [-vy   vx    0 ]
696/// ```
697#[inline]
698pub fn skew_symmetric(v: &Vector3<f64>) -> Matrix3<f64> {
699    Matrix3::new(0.0, -v.z, v.y, v.z, 0.0, -v.x, -v.y, v.x, 0.0)
700}
701
702#[cfg(test)]
703mod tests {
704    use super::*;
705    use crate::pinhole::PinholeCamera;
706    use apex_manifolds::LieGroup;
707    use apex_manifolds::se3::{SE3, SE3Tangent};
708
709    type TestResult = Result<(), Box<dyn std::error::Error>>;
710
711    /// Canonical test for the default `jacobian_pose` implementation (right perturbation).
712    ///
713    /// Since `jacobian_pose` has a single default implementation shared by all models
714    /// except BAL, we test it once here using `PinholeCamera` as a representative model.
715    #[test]
716    fn test_jacobian_pose_numerical() -> TestResult {
717        let pinhole = PinholeParams::new(500.0, 500.0, 320.0, 240.0)?;
718        let camera = PinholeCamera::new(pinhole, DistortionModel::None)?;
719        let pose = SE3::from_translation_euler(0.1, -0.2, 0.3, 0.05, -0.1, 0.15);
720        let p_world = Vector3::new(1.0, 0.5, 3.0);
721
722        let (d_uv_d_pcam, d_pcam_d_pose) = camera.jacobian_pose(&p_world, &pose);
723        let d_uv_d_pose = d_uv_d_pcam * d_pcam_d_pose;
724
725        let eps = NUMERICAL_DERIVATIVE_EPS;
726
727        for i in 0..6 {
728            let mut d = [0.0f64; 6];
729            d[i] = eps;
730            let delta_plus = SE3Tangent::from_components(d[0], d[1], d[2], d[3], d[4], d[5]);
731            d[i] = -eps;
732            let delta_minus = SE3Tangent::from_components(d[0], d[1], d[2], d[3], d[4], d[5]);
733
734            // Right perturbation on T_wc: pose' = pose · Exp(δ)
735            let p_cam_plus = pose.plus(&delta_plus, None, None).act(&p_world, None, None);
736            let p_cam_minus = pose
737                .plus(&delta_minus, None, None)
738                .act(&p_world, None, None);
739
740            let uv_plus = camera.project(&p_cam_plus)?;
741            let uv_minus = camera.project(&p_cam_minus)?;
742
743            let num_deriv = (uv_plus - uv_minus) / (2.0 * eps);
744
745            for r in 0..2 {
746                let analytical = d_uv_d_pose[(r, i)];
747                let numerical = num_deriv[r];
748                let rel_err = (analytical - numerical).abs() / (1.0 + numerical.abs());
749                assert!(
750                    rel_err < JACOBIAN_TEST_TOLERANCE,
751                    "jacobian_pose mismatch at ({r},{i}): analytical={analytical}, numerical={numerical}"
752                );
753            }
754        }
755        Ok(())
756    }
757
758    #[test]
759    fn test_skew_symmetric() {
760        let v = Vector3::new(1.0, 2.0, 3.0);
761        let skew = skew_symmetric(&v);
762
763        assert_eq!(skew[(0, 0)], 0.0);
764        assert_eq!(skew[(1, 1)], 0.0);
765        assert_eq!(skew[(2, 2)], 0.0);
766
767        assert_eq!(skew[(0, 1)], -skew[(1, 0)]);
768        assert_eq!(skew[(0, 2)], -skew[(2, 0)]);
769        assert_eq!(skew[(1, 2)], -skew[(2, 1)]);
770
771        assert_eq!(skew[(0, 1)], -v.z);
772        assert_eq!(skew[(0, 2)], v.y);
773        assert_eq!(skew[(1, 0)], v.z);
774        assert_eq!(skew[(1, 2)], -v.x);
775        assert_eq!(skew[(2, 0)], -v.y);
776        assert_eq!(skew[(2, 1)], v.x);
777
778        let w = Vector3::new(4.0, 5.0, 6.0);
779        let cross_via_skew = skew * w;
780        let cross_direct = v.cross(&w);
781        assert!((cross_via_skew - cross_direct).norm() < 1e-10);
782    }
783}