Skip to main content

apex_camera_models/
kannala_brandt.rs

1//! Kannala-Brandt Fisheye Camera Model
2//!
3//! A widely-used fisheye camera model with polynomial radial distortion,
4//! commonly implemented in OpenCV for fisheye lens calibration.
5//!
6//! # Mathematical Model
7//!
8//! ## Projection (3D → 2D)
9//!
10//! For a 3D point p = (x, y, z) in camera coordinates:
11//!
12//! ```text
13//! r = √(x² + y²)
14//! θ = atan2(r, z)
15//! θ_d = θ·(1 + k₁·θ² + k₂·θ⁴ + k₃·θ⁶ + k₄·θ⁸)
16//! u = fx · θ_d · (x/r) + cx
17//! v = fy · θ_d · (y/r) + cy
18//! ```
19//!
20//! Or equivalently: d(θ) = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
21//!
22//! ## Unprojection (2D → 3D)
23//!
24//! Uses Newton-Raphson iteration to solve for θ from θ_d, then recovers
25//! the 3D ray direction.
26//!
27//! # Parameters
28//!
29//! - **Intrinsics**: fx, fy, cx, cy
30//! - **Distortion**: k₁, k₂, k₃, k₄ (8 parameters total)
31//!
32//! # Use Cases
33//!
34//! - Fisheye cameras with up to 180° field of view
35//! - Wide-angle surveillance cameras
36//! - Automotive and robotics applications
37//! - OpenCV fisheye calibration
38//!
39//! # References
40//!
41//! - Kannala & Brandt, "A Generic Camera Model and Calibration Method for
42//!   Conventional, Wide-Angle, and Fish-Eye Lenses", PAMI 2006
43
44use crate::{CameraModel, CameraModelError, DistortionModel, PinholeParams};
45use nalgebra::{DVector, SMatrix, Vector2, Vector3};
46
47/// Kannala-Brandt fisheye camera model with 8 parameters.
48#[derive(Debug, Clone, Copy, PartialEq)]
49pub struct KannalaBrandtCamera {
50    pub pinhole: PinholeParams,
51    pub distortion: DistortionModel,
52}
53
54impl KannalaBrandtCamera {
55    /// Create a new Kannala-Brandt fisheye camera.
56    ///
57    /// # Arguments
58    ///
59    /// * `pinhole` - Pinhole parameters (fx, fy, cx, cy).
60    /// * `distortion` - MUST be [`DistortionModel::KannalaBrandt`] with `k1`, `k2`, `k3`, `k4`.
61    ///
62    /// # Returns
63    ///
64    /// Returns a new `KannalaBrandtCamera` instance if the distortion model matches.
65    ///
66    /// # Errors
67    ///
68    /// Returns [`CameraModelError::InvalidParams`] if `distortion` is not [`DistortionModel::KannalaBrandt`].
69    pub fn new(
70        pinhole: PinholeParams,
71        distortion: DistortionModel,
72    ) -> Result<Self, CameraModelError> {
73        let model = Self {
74            pinhole,
75            distortion,
76        };
77        model.validate_params()?;
78        Ok(model)
79    }
80
81    /// Helper method to extract distortion parameters.
82    ///
83    /// # Returns
84    ///
85    /// Returns a tuple `(k1, k2, k3, k4)` of distortion coefficients.
86    /// If the distortion model is incorrect (which shouldn't happen for valid instances), returns zeros.
87    fn distortion_params(&self) -> (f64, f64, f64, f64) {
88        match self.distortion {
89            DistortionModel::KannalaBrandt { k1, k2, k3, k4 } => (k1, k2, k3, k4),
90            _ => (0.0, 0.0, 0.0, 0.0),
91        }
92    }
93
94    /// Checks the geometric condition for a valid projection.
95    ///
96    /// # Arguments
97    ///
98    /// * `z` - The z-coordinate of the point in the camera frame.
99    ///
100    /// # Returns
101    ///
102    /// Returns `true` if `z > f64::EPSILON`, `false` otherwise.
103    fn check_projection_condition(&self, z: f64) -> bool {
104        z > f64::EPSILON
105    }
106
107    /// Performs linear estimation to initialize distortion parameters from point correspondences.
108    ///
109    /// This method estimates the distortion coefficients [k1, k2, k3, k4] using a linear
110    /// least squares approach given 3D-2D point correspondences. It assumes the intrinsic
111    /// parameters (fx, fy, cx, cy) are already set.
112    ///
113    /// # Arguments
114    ///
115    /// * `points_3d`: Matrix3xX<f64> - 3D points in camera coordinates (each column is a point)
116    /// * `points_2d`: Matrix2xX<f64> - Corresponding 2D points in image coordinates
117    ///
118    /// # Returns
119    ///
120    /// Returns `Ok(())` on success or a `CameraModelError` if the estimation fails.
121    pub fn linear_estimation(
122        &mut self,
123        points_3d: &nalgebra::Matrix3xX<f64>,
124        points_2d: &nalgebra::Matrix2xX<f64>,
125    ) -> Result<(), CameraModelError> {
126        if points_3d.ncols() != points_2d.ncols() {
127            return Err(CameraModelError::InvalidParams(
128                "Number of 2D and 3D points must match".to_string(),
129            ));
130        }
131        if points_3d.ncols() < 4 {
132            return Err(CameraModelError::InvalidParams(
133                "Not enough points for linear estimation (need at least 4)".to_string(),
134            ));
135        }
136
137        let num_points = points_3d.ncols();
138        let mut a_mat = nalgebra::DMatrix::zeros(num_points * 2, 4);
139        let mut b_vec = nalgebra::DVector::zeros(num_points * 2);
140
141        for i in 0..num_points {
142            let p3d = points_3d.column(i);
143            let p2d = points_2d.column(i);
144
145            let x_world = p3d.x;
146            let y_world = p3d.y;
147            let z_world = p3d.z;
148
149            let u_img = p2d.x;
150            let v_img = p2d.y;
151
152            if z_world <= f64::EPSILON {
153                continue;
154            }
155
156            let r_world = (x_world * x_world + y_world * y_world).sqrt();
157            let theta = r_world.atan2(z_world);
158
159            let theta2 = theta * theta;
160            let theta3 = theta2 * theta;
161            let theta5 = theta3 * theta2;
162            let theta7 = theta5 * theta2;
163            let theta9 = theta7 * theta2;
164
165            a_mat[(i * 2, 0)] = theta3;
166            a_mat[(i * 2, 1)] = theta5;
167            a_mat[(i * 2, 2)] = theta7;
168            a_mat[(i * 2, 3)] = theta9;
169
170            a_mat[(i * 2 + 1, 0)] = theta3;
171            a_mat[(i * 2 + 1, 1)] = theta5;
172            a_mat[(i * 2 + 1, 2)] = theta7;
173            a_mat[(i * 2 + 1, 3)] = theta9;
174
175            let x_r = if r_world < f64::EPSILON {
176                0.0
177            } else {
178                x_world / r_world
179            };
180            let y_r = if r_world < f64::EPSILON {
181                0.0
182            } else {
183                y_world / r_world
184            };
185
186            if (self.pinhole.fx * x_r).abs() < f64::EPSILON && x_r.abs() > f64::EPSILON {
187                return Err(CameraModelError::NumericalError {
188                    operation: "linear_estimation".to_string(),
189                    details: "fx * x_r is zero in linear estimation".to_string(),
190                });
191            }
192            if (self.pinhole.fy * y_r).abs() < f64::EPSILON && y_r.abs() > f64::EPSILON {
193                return Err(CameraModelError::NumericalError {
194                    operation: "linear_estimation".to_string(),
195                    details: "fy * y_r is zero in linear estimation".to_string(),
196                });
197            }
198
199            if x_r.abs() > f64::EPSILON {
200                b_vec[i * 2] = (u_img - self.pinhole.cx) / (self.pinhole.fx * x_r) - theta;
201            } else {
202                b_vec[i * 2] = if (u_img - self.pinhole.cx).abs() < f64::EPSILON {
203                    -theta
204                } else {
205                    0.0
206                };
207            }
208
209            if y_r.abs() > f64::EPSILON {
210                b_vec[i * 2 + 1] = (v_img - self.pinhole.cy) / (self.pinhole.fy * y_r) - theta;
211            } else {
212                b_vec[i * 2 + 1] = if (v_img - self.pinhole.cy).abs() < f64::EPSILON {
213                    -theta
214                } else {
215                    0.0
216                };
217            }
218        }
219
220        let svd = a_mat.svd(true, true);
221        let x_coeffs =
222            svd.solve(&b_vec, f64::EPSILON)
223                .map_err(|e_str| CameraModelError::NumericalError {
224                    operation: "svd_solve".to_string(),
225                    details: format!("SVD solve failed in linear estimation: {e_str}"),
226                })?;
227
228        self.distortion = DistortionModel::KannalaBrandt {
229            k1: x_coeffs[0],
230            k2: x_coeffs[1],
231            k3: x_coeffs[2],
232            k4: x_coeffs[3],
233        };
234
235        self.validate_params()?;
236        Ok(())
237    }
238}
239
240/// Convert camera to dynamic vector of intrinsic parameters.
241///
242/// # Layout
243///
244/// The parameters are ordered as: [fx, fy, cx, cy, k1, k2, k3, k4]
245impl From<&KannalaBrandtCamera> for DVector<f64> {
246    fn from(camera: &KannalaBrandtCamera) -> Self {
247        let (k1, k2, k3, k4) = camera.distortion_params();
248        DVector::from_vec(vec![
249            camera.pinhole.fx,
250            camera.pinhole.fy,
251            camera.pinhole.cx,
252            camera.pinhole.cy,
253            k1,
254            k2,
255            k3,
256            k4,
257        ])
258    }
259}
260
261/// Convert camera to fixed-size array of intrinsic parameters.
262///
263/// # Layout
264///
265/// The parameters are ordered as: [fx, fy, cx, cy, k1, k2, k3, k4]
266impl From<&KannalaBrandtCamera> for [f64; 8] {
267    fn from(camera: &KannalaBrandtCamera) -> Self {
268        let (k1, k2, k3, k4) = camera.distortion_params();
269        [
270            camera.pinhole.fx,
271            camera.pinhole.fy,
272            camera.pinhole.cx,
273            camera.pinhole.cy,
274            k1,
275            k2,
276            k3,
277            k4,
278        ]
279    }
280}
281
282/// Create camera from slice of intrinsic parameters.
283///
284/// # Layout
285///
286/// Expected parameter order: [fx, fy, cx, cy, k1, k2, k3, k4]
287///
288/// # Panics
289///
290/// Panics if the slice has fewer than 8 elements.
291impl From<&[f64]> for KannalaBrandtCamera {
292    fn from(params: &[f64]) -> Self {
293        assert!(
294            params.len() >= 8,
295            "KannalaBrandtCamera requires at least 8 parameters, got {}",
296            params.len()
297        );
298        Self {
299            pinhole: PinholeParams {
300                fx: params[0],
301                fy: params[1],
302                cx: params[2],
303                cy: params[3],
304            },
305            distortion: DistortionModel::KannalaBrandt {
306                k1: params[4],
307                k2: params[5],
308                k3: params[6],
309                k4: params[7],
310            },
311        }
312    }
313}
314
315/// Create camera from fixed-size array of intrinsic parameters.
316///
317/// # Layout
318///
319/// Expected parameter order: [fx, fy, cx, cy, k1, k2, k3, k4]
320impl From<[f64; 8]> for KannalaBrandtCamera {
321    fn from(params: [f64; 8]) -> Self {
322        Self {
323            pinhole: PinholeParams {
324                fx: params[0],
325                fy: params[1],
326                cx: params[2],
327                cy: params[3],
328            },
329            distortion: DistortionModel::KannalaBrandt {
330                k1: params[4],
331                k2: params[5],
332                k3: params[6],
333                k4: params[7],
334            },
335        }
336    }
337}
338
339/// Creates a `KannalaBrandtCamera` from a parameter slice with validation.
340///
341/// Unlike `From<&[f64]>`, this constructor validates all parameters
342/// and returns a `Result` instead of panicking on invalid input.
343///
344/// # Errors
345///
346/// Returns `CameraModelError::InvalidParams` if fewer than 8 parameters are provided.
347/// Returns validation errors if focal lengths are non-positive or parameters are non-finite.
348pub fn try_from_params(params: &[f64]) -> Result<KannalaBrandtCamera, CameraModelError> {
349    if params.len() < 8 {
350        return Err(CameraModelError::InvalidParams(format!(
351            "KannalaBrandtCamera requires at least 8 parameters, got {}",
352            params.len()
353        )));
354    }
355    let camera = KannalaBrandtCamera::from(params);
356    camera.validate_params()?;
357    Ok(camera)
358}
359
360impl CameraModel for KannalaBrandtCamera {
361    const INTRINSIC_DIM: usize = 8;
362    type IntrinsicJacobian = SMatrix<f64, 2, 8>;
363    type PointJacobian = SMatrix<f64, 2, 3>;
364
365    /// Projects a 3D point to 2D image coordinates.
366    ///
367    /// # Mathematical Formula
368    ///
369    /// ```text
370    /// r = √(x² + y²)
371    /// θ = atan2(r, z)
372    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
373    /// u = fx · θ_d · (x/r) + cx
374    /// v = fy · θ_d · (y/r) + cy
375    /// ```
376    ///
377    /// # Arguments
378    ///
379    /// * `p_cam` - 3D point in camera coordinate frame.
380    ///
381    /// # Returns
382    ///
383    /// - `Ok(uv)` - 2D image coordinates if valid.
384    ///
385    /// # Errors
386    ///
387    /// Returns [`CameraModelError::InvalidParams`] if point is behind camera (z <= EPSILON).
388    fn project(&self, p_cam: &Vector3<f64>) -> Result<Vector2<f64>, CameraModelError> {
389        let x = p_cam[0];
390        let y = p_cam[1];
391        let z = p_cam[2];
392
393        // Check if point is valid for projection (in front of camera)
394        if !self.check_projection_condition(z) {
395            return Err(CameraModelError::PointBehindCamera {
396                z,
397                min_z: f64::EPSILON,
398            });
399        }
400
401        let (k1, k2, k3, k4) = self.distortion_params();
402        let r2 = x * x + y * y;
403        let r = r2.sqrt();
404        let theta = r.atan2(z);
405
406        // Polynomial distortion: d(θ) = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
407        let theta2 = theta * theta;
408        let theta3 = theta2 * theta;
409        let theta5 = theta3 * theta2;
410        let theta7 = theta5 * theta2;
411        let theta9 = theta7 * theta2;
412
413        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
414
415        if r < crate::GEOMETRIC_PRECISION {
416            // Point near optical axis: x/r and y/r are unstable.
417            // Limit approaches (fx * (theta_d/r) * x + cx)
418            // theta ~ r/z (for small theta), theta_d ~ theta (for small theta)
419            // theta_d/r ~ 1/z.
420            // u = fx * x/z + cx, v = fy * y/z + cy.
421            // Effectively pinhole close to center.
422            let inv_z = 1.0 / z;
423            return Ok(Vector2::new(
424                self.pinhole.fx * x * inv_z + self.pinhole.cx,
425                self.pinhole.fy * y * inv_z + self.pinhole.cy,
426            ));
427        }
428
429        let inv_r = 1.0 / r;
430        Ok(Vector2::new(
431            self.pinhole.fx * theta_d * x * inv_r + self.pinhole.cx,
432            self.pinhole.fy * theta_d * y * inv_r + self.pinhole.cy,
433        ))
434    }
435
436    /// Unprojects a 2D image point to a 3D ray.
437    ///
438    /// # Algorithm
439    ///
440    /// Newton-Raphson iteration to solve for θ from θ_d:
441    /// - f(θ) = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹ - θ_d = 0
442    /// - f'(θ) = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
443    ///
444    /// # Arguments
445    ///
446    /// * `point_2d` - 2D point in image coordinates.
447    ///
448    /// # Returns
449    ///
450    /// - `Ok(ray)` - Normalized 3D ray direction.
451    ///
452    /// # Errors
453    ///
454    /// Returns [`CameraModelError::NumericalError`] if Newton-Raphson fails to converge or derivative is too small.
455    fn unproject(&self, point_2d: &Vector2<f64>) -> Result<Vector3<f64>, CameraModelError> {
456        let u = point_2d.x;
457        let v = point_2d.y;
458
459        let (k1, k2, k3, k4) = self.distortion_params();
460        let mx = (u - self.pinhole.cx) / self.pinhole.fx;
461        let my = (v - self.pinhole.cy) / self.pinhole.fy;
462
463        let mut ru = (mx * mx + my * my).sqrt();
464
465        // Clamp undistorted radius to π/2 to ensure Newton-Raphson stability.
466        // For the Kannala-Brandt model, θ ∈ [0, π/2] maps the maximum valid
467        // field of view (180° full angle). Values beyond this produce physically
468        // meaningless results and can cause the iterative solver to diverge.
469        // Reference: Kannala & Brandt, "A Generic Camera Model and Calibration
470        // Method for Conventional, Wide-Angle, and Fish-Eye Lenses", PAMI 2006.
471        ru = ru.min(std::f64::consts::PI / 2.0);
472
473        if ru < crate::GEOMETRIC_PRECISION {
474            return Ok(Vector3::new(0.0, 0.0, 1.0));
475        }
476
477        // Newton-Raphson
478        let mut theta = ru; // Initial guess
479        const MAX_ITER: usize = 10;
480        const CONVERGENCE_THRESHOLD: f64 = crate::CONVERGENCE_THRESHOLD;
481
482        for _ in 0..MAX_ITER {
483            let theta2 = theta * theta;
484            let theta4 = theta2 * theta2;
485            let theta6 = theta4 * theta2;
486            let theta8 = theta4 * theta4;
487
488            let k1_theta2 = k1 * theta2;
489            let k2_theta4 = k2 * theta4;
490            let k3_theta6 = k3 * theta6;
491            let k4_theta8 = k4 * theta8;
492
493            // f(θ)
494            let f = theta * (1.0 + k1_theta2 + k2_theta4 + k3_theta6 + k4_theta8) - ru;
495
496            // f'(θ)
497            let f_prime =
498                1.0 + 3.0 * k1_theta2 + 5.0 * k2_theta4 + 7.0 * k3_theta6 + 9.0 * k4_theta8;
499
500            if f_prime.abs() < f64::EPSILON {
501                return Err(CameraModelError::NumericalError {
502                    operation: "unprojection".to_string(),
503                    details: "Derivative too small in KB unprojection".to_string(),
504                });
505            }
506
507            let delta = f / f_prime;
508            theta -= delta;
509
510            if delta.abs() < CONVERGENCE_THRESHOLD {
511                break;
512            }
513        }
514
515        // Convert θ to 3D ray
516        let sin_theta = theta.sin();
517        let cos_theta = theta.cos();
518
519        // Direction in xy plane
520        // if ru is small we returned already.
521        // x = mx * sin(theta) / ru
522        // y = my * sin(theta) / ru
523        let scale = sin_theta / ru;
524        let x = mx * scale;
525        let y = my * scale;
526        let z = cos_theta;
527
528        Ok(Vector3::new(x, y, z).normalize())
529    }
530
531    /// Jacobian of projection w.r.t. 3D point coordinates (2×3).
532    ///
533    /// Computes ∂π/∂p where π is the projection function and p = (x, y, z) is the 3D point.
534    ///
535    /// # Mathematical Derivation
536    ///
537    /// ## Kannala-Brandt Projection Model Recap
538    ///
539    /// ```text
540    /// r = √(x² + y²)                              // Radial distance from optical axis
541    /// θ = atan2(r, z)                             // Angle from optical axis
542    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹    // Distorted angle (polynomial)
543    /// u = fx · θ_d · (x/r) + cx                  // Pixel u-coordinate
544    /// v = fy · θ_d · (y/r) + cy                  // Pixel v-coordinate
545    /// ```
546    ///
547    /// Derivatives of intermediate quantities:
548    /// ```text
549    /// ∂r/∂x = x/r,  ∂r/∂y = y/r,  ∂r/∂z = 0
550    /// ∂θ/∂x = z·x / (r·(r²+z²))
551    /// ∂θ/∂y = z·y / (r·(r²+z²))
552    /// ∂θ/∂z = -r / (r²+z²)
553    /// ∂θ_d/∂θ = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
554    /// ∂θ_d/∂x = (∂θ_d/∂θ) · (∂θ/∂x)
555    /// ∂θ_d/∂y = (∂θ_d/∂θ) · (∂θ/∂y)
556    /// ∂θ_d/∂z = (∂θ_d/∂θ) · (∂θ/∂z)
557    /// ```
558    ///
559    /// Derivatives of pixel coordinates (quotient + product rule):
560    ///
561    /// For u = fx · θ_d · (x/r) + cx:
562    /// ```text
563    /// ∂u/∂x = fx · [∂θ_d/∂x · (x/r) + θ_d · ∂(x/r)/∂x]
564    ///       = fx · [∂θ_d/∂x · (x/r) + θ_d · (1/r - x²/r³)]
565    ///
566    /// ∂u/∂y = fx · [∂θ_d/∂y · (x/r) + θ_d · (-x·y/r³)]
567    ///
568    /// ∂u/∂z = fx · [∂θ_d/∂z · (x/r)]
569    /// ```
570    ///
571    /// Similarly for v = fy · θ_d · (y/r) + cy:
572    /// ```text
573    /// ∂v/∂x = fy · [∂θ_d/∂x · (y/r) + θ_d · (-x·y/r³)]
574    ///
575    /// ∂v/∂y = fy · [∂θ_d/∂y · (y/r) + θ_d · (1/r - y²/r³)]
576    ///
577    /// ∂v/∂z = fy · [∂θ_d/∂z · (y/r)]
578    /// ```
579    ///
580    /// Near optical axis (r → 0): Use simplified Jacobian for numerical stability:
581    /// ```text
582    /// ∂u/∂x ≈ fx · (∂θ_d/∂θ) / z
583    /// ∂v/∂y ≈ fy · (∂θ_d/∂θ) / z
584    /// (all other terms ≈ 0)
585    /// ```
586    ///
587    /// Final Jacobian matrix (2×3):
588    ///
589    /// ```text
590    /// J = [ ∂u/∂x  ∂u/∂y  ∂u/∂z ]
591    ///     [ ∂v/∂x  ∂v/∂y  ∂v/∂z ]
592    /// ```
593    ///
594    /// # Arguments
595    ///
596    /// * `p_cam` - 3D point in camera coordinate frame.
597    ///
598    /// # Returns
599    ///
600    /// Returns the 2×3 Jacobian matrix.
601    ///
602    /// # References
603    ///
604    /// - Kannala & Brandt, "A Generic Camera Model and Calibration Method for Conventional,
605    ///   Wide-Angle, and Fish-Eye Lenses", IEEE PAMI 2006
606    /// - Verified against numerical differentiation in `test_jacobian_point_numerical()`
607    ///
608    /// # Implementation Note
609    ///
610    /// The implementation handles the optical axis singularity (r → 0) using a threshold check
611    /// and falls back to a simplified Jacobian for numerical stability.
612    fn jacobian_point(&self, p_cam: &Vector3<f64>) -> Self::PointJacobian {
613        let x = p_cam[0];
614        let y = p_cam[1];
615        let z = p_cam[2];
616
617        let (k1, k2, k3, k4) = self.distortion_params();
618        let r = (x * x + y * y).sqrt();
619        let theta = r.atan2(z);
620
621        let theta2 = theta * theta;
622        let theta3 = theta2 * theta;
623        let theta5 = theta3 * theta2;
624        let theta7 = theta5 * theta2;
625        let theta9 = theta7 * theta2;
626
627        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
628
629        // ∂θ_d/∂θ = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
630        let dtheta_d_dtheta = 1.0
631            + 3.0 * k1 * theta2
632            + 5.0 * k2 * theta2 * theta2
633            + 7.0 * k3 * theta2 * theta2 * theta2
634            + 9.0 * k4 * theta2 * theta2 * theta2 * theta2;
635
636        if r < crate::GEOMETRIC_PRECISION {
637            // Near optical axis, use simplified Jacobian
638            return SMatrix::<f64, 2, 3>::new(
639                self.pinhole.fx * dtheta_d_dtheta / z,
640                0.0,
641                0.0,
642                0.0,
643                self.pinhole.fy * dtheta_d_dtheta / z,
644                0.0,
645            );
646        }
647
648        let inv_r = 1.0 / r;
649        let r2 = r * r;
650        let r_z2 = r2 + z * z;
651
652        // ∂θ/∂x = z·x / (r·(r² + z²))
653        // ∂θ/∂y = z·y / (r·(r² + z²))
654        // ∂θ/∂z = -r / (r² + z²)
655        let dtheta_dx = z * x / (r * r_z2);
656        let dtheta_dy = z * y / (r * r_z2);
657        let dtheta_dz = -r / r_z2;
658
659        // ∂r/∂x = x/r, ∂r/∂y = y/r, ∂r/∂z = 0
660
661        // Chain rule for u = fx · θ_d · (x/r) + cx
662        let inv_r2 = inv_r * inv_r;
663
664        let du_dx = self.pinhole.fx
665            * (dtheta_d_dtheta * dtheta_dx * x * inv_r
666                + theta_d * (inv_r - x * x * inv_r2 * inv_r));
667        let du_dy = self.pinhole.fx
668            * (dtheta_d_dtheta * dtheta_dy * x * inv_r - theta_d * x * y * inv_r2 * inv_r);
669        let du_dz = self.pinhole.fx * dtheta_d_dtheta * dtheta_dz * x * inv_r;
670
671        let dv_dx = self.pinhole.fy
672            * (dtheta_d_dtheta * dtheta_dx * y * inv_r - theta_d * x * y * inv_r2 * inv_r);
673        let dv_dy = self.pinhole.fy
674            * (dtheta_d_dtheta * dtheta_dy * y * inv_r
675                + theta_d * (inv_r - y * y * inv_r2 * inv_r));
676        let dv_dz = self.pinhole.fy * dtheta_d_dtheta * dtheta_dz * y * inv_r;
677
678        SMatrix::<f64, 2, 3>::new(du_dx, du_dy, du_dz, dv_dx, dv_dy, dv_dz)
679    }
680
681    /// Jacobian of projection w.r.t. intrinsic parameters (2×8).
682    ///
683    /// Computes ∂π/∂K where K = [fx, fy, cx, cy, k₁, k₂, k₃, k₄] are the intrinsic parameters.
684    ///
685    /// # Mathematical Derivation
686    ///
687    /// The intrinsic parameters consist of:
688    /// 1. **Linear parameters**: fx, fy, cx, cy (pinhole projection)
689    /// 2. **Distortion parameters**: k₁, k₂, k₃, k₄ (Kannala-Brandt polynomial coefficients)
690    ///
691    /// ## Kannala-Brandt Projection Model Recap
692    ///
693    /// ```text
694    /// r = √(x² + y²)
695    /// θ = atan2(r, z)
696    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
697    /// u = fx · θ_d · (x/r) + cx
698    /// v = fy · θ_d · (y/r) + cy
699    /// ```
700    ///
701    /// Linear parameters (fx, fy, cx, cy):
702    /// ```text
703    /// ∂u/∂fx = θ_d · (x/r),  ∂u/∂fy = 0,  ∂u/∂cx = 1,  ∂u/∂cy = 0
704    /// ∂v/∂fx = 0,  ∂v/∂fy = θ_d · (y/r),  ∂v/∂cx = 0,  ∂v/∂cy = 1
705    /// ```
706    ///
707    /// Distortion parameters (k₁, k₂, k₃, k₄):
708    ///
709    /// The distortion affects θ_d through the polynomial expansion.
710    ///
711    /// ### Derivatives of θ_d:
712    /// ```text
713    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
714    ///
715    /// ∂θ_d/∂k₁ = θ³
716    /// ∂θ_d/∂k₂ = θ⁵
717    /// ∂θ_d/∂k₃ = θ⁷
718    /// ∂θ_d/∂k₄ = θ⁹
719    /// ```
720    ///
721    /// ### Chain rule to pixel coordinates:
722    ///
723    /// For u = fx · θ_d · (x/r) + cx:
724    /// ```text
725    /// ∂u/∂k₁ = fx · (∂θ_d/∂k₁) · (x/r) = fx · θ³ · (x/r)
726    /// ∂u/∂k₂ = fx · θ⁵ · (x/r)
727    /// ∂u/∂k₃ = fx · θ⁷ · (x/r)
728    /// ∂u/∂k₄ = fx · θ⁹ · (x/r)
729    /// ```
730    ///
731    /// Similarly for v = fy · θ_d · (y/r) + cy:
732    /// ```text
733    /// ∂v/∂k₁ = fy · θ³ · (y/r)
734    /// ∂v/∂k₂ = fy · θ⁵ · (y/r)
735    /// ∂v/∂k₃ = fy · θ⁷ · (y/r)
736    /// ∂v/∂k₄ = fy · θ⁹ · (y/r)
737    /// ```
738    ///
739    /// ## Final Jacobian Matrix (2×8)
740    ///
741    /// ```text
742    /// J = [ ∂u/∂fx  ∂u/∂fy  ∂u/∂cx  ∂u/∂cy  ∂u/∂k₁  ∂u/∂k₂  ∂u/∂k₃  ∂u/∂k₄ ]
743    ///     [ ∂v/∂fx  ∂v/∂fy  ∂v/∂cx  ∂v/∂cy  ∂v/∂k₁  ∂v/∂k₂  ∂v/∂k₃  ∂v/∂k₄ ]
744    /// ```
745    ///
746    /// Expanded:
747    /// ```text
748    /// J = [ θ_d·x/r    0       1    0    fx·θ³·x/r  fx·θ⁵·x/r  fx·θ⁷·x/r  fx·θ⁹·x/r ]
749    ///     [    0    θ_d·y/r    0    1    fy·θ³·y/r  fy·θ⁵·y/r  fy·θ⁷·y/r  fy·θ⁹·y/r ]
750    /// ```
751    ///
752    /// # Arguments
753    ///
754    /// * `p_cam` - 3D point in camera coordinate frame.
755    ///
756    /// # Returns
757    ///
758    /// Returns the 2×8 intrinsic Jacobian matrix.
759    ///
760    /// # References
761    ///
762    /// - Kannala & Brandt, "A Generic Camera Model and Calibration Method for Conventional,
763    ///   Wide-Angle, and Fish-Eye Lenses", IEEE PAMI 2006
764    /// - Verified against numerical differentiation in `test_jacobian_intrinsics_numerical()`
765    ///
766    /// # Implementation Note
767    ///
768    /// For numerical stability, when r (radial distance) is very small (near optical axis),
769    /// the Jacobian is set to zero as the projection becomes degenerate in this region.
770    fn jacobian_intrinsics(&self, p_cam: &Vector3<f64>) -> Self::IntrinsicJacobian {
771        let x = p_cam[0];
772        let y = p_cam[1];
773        let z = p_cam[2];
774
775        let (k1, k2, k3, k4) = self.distortion_params();
776        let r = (x * x + y * y).sqrt();
777        let theta = r.atan2(z);
778
779        let theta2 = theta * theta;
780        let theta3 = theta2 * theta;
781        let theta5 = theta3 * theta2;
782        let theta7 = theta5 * theta2;
783        let theta9 = theta7 * theta2;
784
785        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
786
787        if r < crate::GEOMETRIC_PRECISION {
788            return SMatrix::<f64, 2, 8>::zeros();
789        }
790
791        let inv_r = 1.0 / r;
792        let x_theta_d_r = x * theta_d * inv_r;
793        let y_theta_d_r = y * theta_d * inv_r;
794
795        // ∂u/∂fx = θ_d·x/r, ∂u/∂fy = 0, ∂u/∂cx = 1, ∂u/∂cy = 0
796        // ∂v/∂fx = 0, ∂v/∂fy = θ_d·y/r, ∂v/∂cx = 0, ∂v/∂cy = 1
797
798        // ∂u/∂k₁ = fx·θ³·x/r, ∂u/∂k₂ = fx·θ⁵·x/r, etc.
799        let du_dk1 = self.pinhole.fx * theta3 * x * inv_r;
800        let du_dk2 = self.pinhole.fx * theta5 * x * inv_r;
801        let du_dk3 = self.pinhole.fx * theta7 * x * inv_r;
802        let du_dk4 = self.pinhole.fx * theta9 * x * inv_r;
803
804        let dv_dk1 = self.pinhole.fy * theta3 * y * inv_r;
805        let dv_dk2 = self.pinhole.fy * theta5 * y * inv_r;
806        let dv_dk3 = self.pinhole.fy * theta7 * y * inv_r;
807        let dv_dk4 = self.pinhole.fy * theta9 * y * inv_r;
808
809        SMatrix::<f64, 2, 8>::from_row_slice(&[
810            x_theta_d_r,
811            0.0,
812            1.0,
813            0.0,
814            du_dk1,
815            du_dk2,
816            du_dk3,
817            du_dk4,
818            0.0,
819            y_theta_d_r,
820            0.0,
821            1.0,
822            dv_dk1,
823            dv_dk2,
824            dv_dk3,
825            dv_dk4,
826        ])
827    }
828
829    /// Validates camera parameters.
830    ///
831    /// # Validation Rules
832    ///
833    /// - `fx`, `fy` must be positive.
834    /// - `fx`, `fy` must be finite.
835    /// - `cx`, `cy` must be finite.
836    /// - `k1`..`k4` must be finite.
837    ///
838    /// # Errors
839    ///
840    /// Returns [`CameraModelError`] if any parameter violates validation rules.
841    fn validate_params(&self) -> Result<(), CameraModelError> {
842        self.pinhole.validate()?;
843        self.get_distortion().validate()
844    }
845
846    /// Returns the pinhole parameters of the camera.
847    ///
848    /// # Returns
849    ///
850    /// A [`PinholeParams`] struct containing the focal lengths (fx, fy) and principal point (cx, cy).
851    fn get_pinhole_params(&self) -> PinholeParams {
852        PinholeParams {
853            fx: self.pinhole.fx,
854            fy: self.pinhole.fy,
855            cx: self.pinhole.cx,
856            cy: self.pinhole.cy,
857        }
858    }
859
860    /// Returns the distortion model and parameters of the camera.
861    ///
862    /// # Returns
863    ///
864    /// The [`DistortionModel`] associated with this camera (typically [`DistortionModel::KannalaBrandt`]).
865    fn get_distortion(&self) -> DistortionModel {
866        self.distortion
867    }
868
869    /// Returns the string identifier for the camera model.
870    ///
871    /// # Returns
872    ///
873    /// The string `"kannala_brandt"`.
874    fn get_model_name(&self) -> &'static str {
875        "kannala_brandt"
876    }
877}
878
879#[cfg(test)]
880mod tests {
881    use super::*;
882    use nalgebra::{Matrix2xX, Matrix3xX};
883
884    type TestResult = Result<(), Box<dyn std::error::Error>>;
885
886    #[test]
887    fn test_kb_camera_creation() -> TestResult {
888        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
889        let distortion = DistortionModel::KannalaBrandt {
890            k1: 0.1,
891            k2: 0.01,
892            k3: 0.001,
893            k4: 0.0001,
894        };
895        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
896        assert_eq!(camera.pinhole.fx, 300.0);
897        let (k1, _, _, _) = camera.distortion_params();
898        assert_eq!(k1, 0.1);
899        Ok(())
900    }
901
902    #[test]
903    fn test_projection_at_optical_axis() -> TestResult {
904        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
905        let distortion = DistortionModel::KannalaBrandt {
906            k1: 0.1,
907            k2: 0.01,
908            k3: 0.001,
909            k4: 0.0001,
910        };
911        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
912        let p_cam = Vector3::new(0.0, 0.0, 1.0);
913        let uv = camera.project(&p_cam)?;
914
915        assert!((uv.x - 320.0).abs() < 1e-6);
916        assert!((uv.y - 240.0).abs() < 1e-6);
917
918        Ok(())
919    }
920
921    #[test]
922    fn test_jacobian_point_numerical() -> TestResult {
923        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
924        let distortion = DistortionModel::KannalaBrandt {
925            k1: 0.1,
926            k2: 0.01,
927            k3: 0.001,
928            k4: 0.0001,
929        };
930        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
931        let p_cam = Vector3::new(0.1, 0.2, 1.0);
932
933        let jac_analytical = camera.jacobian_point(&p_cam);
934        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
935
936        for i in 0..3 {
937            let mut p_plus = p_cam;
938            let mut p_minus = p_cam;
939            p_plus[i] += eps;
940            p_minus[i] -= eps;
941
942            let uv_plus = camera.project(&p_plus)?;
943            let uv_minus = camera.project(&p_minus)?;
944            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
945
946            for r in 0..2 {
947                assert!(
948                    jac_analytical[(r, i)].is_finite(),
949                    "Jacobian [{r},{i}] is not finite"
950                );
951                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
952                assert!(
953                    diff < crate::JACOBIAN_TEST_TOLERANCE,
954                    "Mismatch at ({}, {})",
955                    r,
956                    i
957                );
958            }
959        }
960        Ok(())
961    }
962
963    #[test]
964    fn test_jacobian_intrinsics_numerical() -> TestResult {
965        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
966        let distortion = DistortionModel::KannalaBrandt {
967            k1: 0.1,
968            k2: 0.01,
969            k3: 0.001,
970            k4: 0.0001,
971        };
972        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
973        let p_cam = Vector3::new(0.1, 0.2, 1.0);
974
975        let jac_analytical = camera.jacobian_intrinsics(&p_cam);
976        let params: DVector<f64> = (&camera).into();
977        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
978
979        for i in 0..8 {
980            let mut params_plus = params.clone();
981            let mut params_minus = params.clone();
982            params_plus[i] += eps;
983            params_minus[i] -= eps;
984
985            let cam_plus = KannalaBrandtCamera::from(params_plus.as_slice());
986            let cam_minus = KannalaBrandtCamera::from(params_minus.as_slice());
987
988            let uv_plus = cam_plus.project(&p_cam)?;
989            let uv_minus = cam_minus.project(&p_cam)?;
990            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
991
992            for r in 0..2 {
993                assert!(
994                    jac_analytical[(r, i)].is_finite(),
995                    "Jacobian [{r},{i}] is not finite"
996                );
997                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
998                assert!(
999                    diff < crate::JACOBIAN_TEST_TOLERANCE,
1000                    "Mismatch at ({}, {})",
1001                    r,
1002                    i
1003                );
1004            }
1005        }
1006        Ok(())
1007    }
1008
1009    #[test]
1010    fn test_kb_from_into_traits() -> TestResult {
1011        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1012        let distortion = DistortionModel::KannalaBrandt {
1013            k1: 0.1,
1014            k2: 0.01,
1015            k3: 0.001,
1016            k4: 0.0001,
1017        };
1018        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1019
1020        // Test conversion to DVector
1021        let params: DVector<f64> = (&camera).into();
1022        assert_eq!(params.len(), 8);
1023        assert_eq!(params[0], 300.0);
1024        assert_eq!(params[1], 300.0);
1025        assert_eq!(params[2], 320.0);
1026        assert_eq!(params[3], 240.0);
1027        assert_eq!(params[4], 0.1);
1028        assert_eq!(params[5], 0.01);
1029        assert_eq!(params[6], 0.001);
1030        assert_eq!(params[7], 0.0001);
1031
1032        // Test conversion to array
1033        let arr: [f64; 8] = (&camera).into();
1034        assert_eq!(arr, [300.0, 300.0, 320.0, 240.0, 0.1, 0.01, 0.001, 0.0001]);
1035
1036        // Test conversion from slice
1037        let params_slice = [350.0, 350.0, 330.0, 250.0, 0.2, 0.02, 0.002, 0.0002];
1038        let camera2 = KannalaBrandtCamera::from(&params_slice[..]);
1039        assert_eq!(camera2.pinhole.fx, 350.0);
1040        assert_eq!(camera2.pinhole.fy, 350.0);
1041        assert_eq!(camera2.pinhole.cx, 330.0);
1042        assert_eq!(camera2.pinhole.cy, 250.0);
1043        let (k1, k2, k3, k4) = camera2.distortion_params();
1044        assert_eq!(k1, 0.2);
1045        assert_eq!(k2, 0.02);
1046        assert_eq!(k3, 0.002);
1047        assert_eq!(k4, 0.0002);
1048
1049        // Test conversion from array
1050        let camera3 =
1051            KannalaBrandtCamera::from([400.0, 400.0, 340.0, 260.0, 0.3, 0.03, 0.003, 0.0003]);
1052        assert_eq!(camera3.pinhole.fx, 400.0);
1053        assert_eq!(camera3.pinhole.fy, 400.0);
1054        let (k1, k2, k3, k4) = camera3.distortion_params();
1055        assert_eq!(k1, 0.3);
1056        assert_eq!(k2, 0.03);
1057        assert_eq!(k3, 0.003);
1058        assert_eq!(k4, 0.0003);
1059
1060        Ok(())
1061    }
1062
1063    #[test]
1064    fn test_linear_estimation() -> TestResult {
1065        // Ground truth fisheye camera
1066        let gt_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1067        let gt_distortion = DistortionModel::KannalaBrandt {
1068            k1: 0.1,
1069            k2: 0.01,
1070            k3: 0.001,
1071            k4: 0.0001,
1072        };
1073        let gt_camera = KannalaBrandtCamera::new(gt_pinhole, gt_distortion)?;
1074
1075        // Generate synthetic 3D points in camera frame
1076        let n_points = 50;
1077        let mut pts_3d = Matrix3xX::zeros(n_points);
1078        let mut pts_2d = Matrix2xX::zeros(n_points);
1079        let mut valid = 0;
1080
1081        for i in 0..n_points {
1082            let angle = i as f64 * 2.0 * std::f64::consts::PI / n_points as f64;
1083            let r = 0.1 + 0.4 * (i as f64 / n_points as f64);
1084            let p3d = Vector3::new(r * angle.cos(), r * angle.sin(), 1.0);
1085
1086            if let Ok(p2d) = gt_camera.project(&p3d) {
1087                pts_3d.set_column(valid, &p3d);
1088                pts_2d.set_column(valid, &p2d);
1089                valid += 1;
1090            }
1091        }
1092        let pts_3d = pts_3d.columns(0, valid).into_owned();
1093        let pts_2d = pts_2d.columns(0, valid).into_owned();
1094
1095        // Initial camera with zero distortion
1096        let init_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1097        let init_distortion = DistortionModel::KannalaBrandt {
1098            k1: 0.0,
1099            k2: 0.0,
1100            k3: 0.0,
1101            k4: 0.0,
1102        };
1103        let mut camera = KannalaBrandtCamera::new(init_pinhole, init_distortion)?;
1104
1105        camera.linear_estimation(&pts_3d, &pts_2d)?;
1106
1107        // Verify reprojection error
1108        for i in 0..valid {
1109            let p3d = pts_3d.column(i).into_owned();
1110            let projected = camera.project(&Vector3::new(p3d.x, p3d.y, p3d.z))?;
1111            let err = ((projected.x - pts_2d[(0, i)]).powi(2)
1112                + (projected.y - pts_2d[(1, i)]).powi(2))
1113            .sqrt();
1114            assert!(err < 3.0, "Reprojection error too large: {err}");
1115        }
1116
1117        Ok(())
1118    }
1119
1120    #[test]
1121    fn test_project_unproject_round_trip() -> TestResult {
1122        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1123        let distortion = DistortionModel::KannalaBrandt {
1124            k1: 0.1,
1125            k2: 0.01,
1126            k3: 0.001,
1127            k4: 0.0001,
1128        };
1129        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1130
1131        let test_points = [
1132            Vector3::new(0.1, 0.2, 1.0),
1133            Vector3::new(-0.3, 0.1, 2.0),
1134            Vector3::new(0.05, -0.1, 0.5),
1135        ];
1136
1137        for p_cam in &test_points {
1138            let uv = camera.project(p_cam)?;
1139            let ray = camera.unproject(&uv)?;
1140            let dot = ray.dot(&p_cam.normalize());
1141            assert!(
1142                (dot - 1.0).abs() < 1e-6,
1143                "Round-trip failed: dot={dot}, expected ~1.0"
1144            );
1145        }
1146
1147        Ok(())
1148    }
1149
1150    #[test]
1151    fn test_project_returns_error_behind_camera() -> TestResult {
1152        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1153        let distortion = DistortionModel::KannalaBrandt {
1154            k1: 0.0,
1155            k2: 0.0,
1156            k3: 0.0,
1157            k4: 0.0,
1158        };
1159        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1160        assert!(camera.project(&Vector3::new(0.0, 0.0, -1.0)).is_err());
1161        Ok(())
1162    }
1163
1164    #[test]
1165    fn test_project_at_min_depth_boundary() -> TestResult {
1166        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1167        let distortion = DistortionModel::KannalaBrandt {
1168            k1: 0.0,
1169            k2: 0.0,
1170            k3: 0.0,
1171            k4: 0.0,
1172        };
1173        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1174        let p_min = Vector3::new(0.0, 0.0, crate::MIN_DEPTH);
1175        if let Ok(uv) = camera.project(&p_min) {
1176            assert!(uv.x.is_finite() && uv.y.is_finite());
1177        }
1178        Ok(())
1179    }
1180}