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 TryFrom<&[f64]> for KannalaBrandtCamera {
292    type Error = CameraModelError;
293
294    fn try_from(params: &[f64]) -> Result<Self, Self::Error> {
295        if params.len() < 8 {
296            return Err(CameraModelError::InvalidParams(format!(
297                "KannalaBrandtCamera requires at least 8 parameters, got {}",
298                params.len()
299            )));
300        }
301        Ok(Self {
302            pinhole: PinholeParams {
303                fx: params[0],
304                fy: params[1],
305                cx: params[2],
306                cy: params[3],
307            },
308            distortion: DistortionModel::KannalaBrandt {
309                k1: params[4],
310                k2: params[5],
311                k3: params[6],
312                k4: params[7],
313            },
314        })
315    }
316}
317
318/// Create camera from fixed-size array of intrinsic parameters.
319///
320/// # Layout
321///
322/// Expected parameter order: [fx, fy, cx, cy, k1, k2, k3, k4]
323impl From<[f64; 8]> for KannalaBrandtCamera {
324    fn from(params: [f64; 8]) -> Self {
325        Self {
326            pinhole: PinholeParams {
327                fx: params[0],
328                fy: params[1],
329                cx: params[2],
330                cy: params[3],
331            },
332            distortion: DistortionModel::KannalaBrandt {
333                k1: params[4],
334                k2: params[5],
335                k3: params[6],
336                k4: params[7],
337            },
338        }
339    }
340}
341
342/// Creates a `KannalaBrandtCamera` from a parameter slice with validation.
343///
344/// Unlike `From<&[f64]>`, this constructor validates all parameters
345/// and returns a `Result` instead of panicking on invalid input.
346///
347/// # Errors
348///
349/// Returns `CameraModelError::InvalidParams` if fewer than 8 parameters are provided.
350/// Returns validation errors if focal lengths are non-positive or parameters are non-finite.
351pub fn try_from_params(params: &[f64]) -> Result<KannalaBrandtCamera, CameraModelError> {
352    let camera = KannalaBrandtCamera::try_from(params)?;
353    camera.validate_params()?;
354    Ok(camera)
355}
356
357impl CameraModel for KannalaBrandtCamera {
358    const INTRINSIC_DIM: usize = 8;
359    type IntrinsicJacobian = SMatrix<f64, 2, 8>;
360    type PointJacobian = SMatrix<f64, 2, 3>;
361
362    /// Projects a 3D point to 2D image coordinates.
363    ///
364    /// # Mathematical Formula
365    ///
366    /// ```text
367    /// r = √(x² + y²)
368    /// θ = atan2(r, z)
369    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
370    /// u = fx · θ_d · (x/r) + cx
371    /// v = fy · θ_d · (y/r) + cy
372    /// ```
373    ///
374    /// # Arguments
375    ///
376    /// * `p_cam` - 3D point in camera coordinate frame.
377    ///
378    /// # Returns
379    ///
380    /// - `Ok(uv)` - 2D image coordinates if valid.
381    ///
382    /// # Errors
383    ///
384    /// Returns [`CameraModelError::InvalidParams`] if point is behind camera (z <= EPSILON).
385    fn project(&self, p_cam: &Vector3<f64>) -> Result<Vector2<f64>, CameraModelError> {
386        let x = p_cam[0];
387        let y = p_cam[1];
388        let z = p_cam[2];
389
390        // Check if point is valid for projection (in front of camera)
391        if !self.check_projection_condition(z) {
392            return Err(CameraModelError::PointBehindCamera {
393                z,
394                min_z: f64::EPSILON,
395            });
396        }
397
398        let (k1, k2, k3, k4) = self.distortion_params();
399        let r2 = x * x + y * y;
400        let r = r2.sqrt();
401        let theta = r.atan2(z);
402
403        // Polynomial distortion: d(θ) = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
404        let theta2 = theta * theta;
405        let theta3 = theta2 * theta;
406        let theta5 = theta3 * theta2;
407        let theta7 = theta5 * theta2;
408        let theta9 = theta7 * theta2;
409
410        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
411
412        if r < crate::GEOMETRIC_PRECISION {
413            // Point near optical axis: x/r and y/r are unstable.
414            // Limit approaches (fx * (theta_d/r) * x + cx)
415            // theta ~ r/z (for small theta), theta_d ~ theta (for small theta)
416            // theta_d/r ~ 1/z.
417            // u = fx * x/z + cx, v = fy * y/z + cy.
418            // Effectively pinhole close to center.
419            let inv_z = 1.0 / z;
420            return Ok(Vector2::new(
421                self.pinhole.fx * x * inv_z + self.pinhole.cx,
422                self.pinhole.fy * y * inv_z + self.pinhole.cy,
423            ));
424        }
425
426        let inv_r = 1.0 / r;
427        Ok(Vector2::new(
428            self.pinhole.fx * theta_d * x * inv_r + self.pinhole.cx,
429            self.pinhole.fy * theta_d * y * inv_r + self.pinhole.cy,
430        ))
431    }
432
433    /// Unprojects a 2D image point to a 3D ray.
434    ///
435    /// # Algorithm
436    ///
437    /// Newton-Raphson iteration to solve for θ from θ_d:
438    /// - f(θ) = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹ - θ_d = 0
439    /// - f'(θ) = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
440    ///
441    /// # Arguments
442    ///
443    /// * `point_2d` - 2D point in image coordinates.
444    ///
445    /// # Returns
446    ///
447    /// - `Ok(ray)` - Normalized 3D ray direction.
448    ///
449    /// # Errors
450    ///
451    /// Returns [`CameraModelError::NumericalError`] if Newton-Raphson fails to converge or derivative is too small.
452    fn unproject(&self, point_2d: &Vector2<f64>) -> Result<Vector3<f64>, CameraModelError> {
453        let u = point_2d.x;
454        let v = point_2d.y;
455
456        let (k1, k2, k3, k4) = self.distortion_params();
457        let mx = (u - self.pinhole.cx) / self.pinhole.fx;
458        let my = (v - self.pinhole.cy) / self.pinhole.fy;
459
460        let mut ru = (mx * mx + my * my).sqrt();
461
462        // Clamp undistorted radius to π/2 to ensure Newton-Raphson stability.
463        // For the Kannala-Brandt model, θ ∈ [0, π/2] maps the maximum valid
464        // field of view (180° full angle). Values beyond this produce physically
465        // meaningless results and can cause the iterative solver to diverge.
466        // Reference: Kannala & Brandt, "A Generic Camera Model and Calibration
467        // Method for Conventional, Wide-Angle, and Fish-Eye Lenses", PAMI 2006.
468        ru = ru.min(std::f64::consts::PI / 2.0);
469
470        if ru < crate::GEOMETRIC_PRECISION {
471            return Ok(Vector3::new(0.0, 0.0, 1.0));
472        }
473
474        // Newton-Raphson
475        let mut theta = ru; // Initial guess
476        const MAX_ITER: usize = 10;
477        const CONVERGENCE_THRESHOLD: f64 = crate::CONVERGENCE_THRESHOLD;
478
479        for _ in 0..MAX_ITER {
480            let theta2 = theta * theta;
481            let theta4 = theta2 * theta2;
482            let theta6 = theta4 * theta2;
483            let theta8 = theta4 * theta4;
484
485            let k1_theta2 = k1 * theta2;
486            let k2_theta4 = k2 * theta4;
487            let k3_theta6 = k3 * theta6;
488            let k4_theta8 = k4 * theta8;
489
490            // f(θ)
491            let f = theta * (1.0 + k1_theta2 + k2_theta4 + k3_theta6 + k4_theta8) - ru;
492
493            // f'(θ)
494            let f_prime =
495                1.0 + 3.0 * k1_theta2 + 5.0 * k2_theta4 + 7.0 * k3_theta6 + 9.0 * k4_theta8;
496
497            if f_prime.abs() < f64::EPSILON {
498                return Err(CameraModelError::NumericalError {
499                    operation: "unprojection".to_string(),
500                    details: "Derivative too small in KB unprojection".to_string(),
501                });
502            }
503
504            let delta = f / f_prime;
505            theta -= delta;
506
507            if delta.abs() < CONVERGENCE_THRESHOLD {
508                break;
509            }
510        }
511
512        // Convert θ to 3D ray
513        let sin_theta = theta.sin();
514        let cos_theta = theta.cos();
515
516        // Direction in xy plane
517        // if ru is small we returned already.
518        // x = mx * sin(theta) / ru
519        // y = my * sin(theta) / ru
520        let scale = sin_theta / ru;
521        let x = mx * scale;
522        let y = my * scale;
523        let z = cos_theta;
524
525        Ok(Vector3::new(x, y, z).normalize())
526    }
527
528    /// Jacobian of projection w.r.t. 3D point coordinates (2×3).
529    ///
530    /// Computes ∂π/∂p where π is the projection function and p = (x, y, z) is the 3D point.
531    ///
532    /// # Mathematical Derivation
533    ///
534    /// ## Kannala-Brandt Projection Model Recap
535    ///
536    /// ```text
537    /// r = √(x² + y²)                              // Radial distance from optical axis
538    /// θ = atan2(r, z)                             // Angle from optical axis
539    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹    // Distorted angle (polynomial)
540    /// u = fx · θ_d · (x/r) + cx                  // Pixel u-coordinate
541    /// v = fy · θ_d · (y/r) + cy                  // Pixel v-coordinate
542    /// ```
543    ///
544    /// Derivatives of intermediate quantities:
545    /// ```text
546    /// ∂r/∂x = x/r,  ∂r/∂y = y/r,  ∂r/∂z = 0
547    /// ∂θ/∂x = z·x / (r·(r²+z²))
548    /// ∂θ/∂y = z·y / (r·(r²+z²))
549    /// ∂θ/∂z = -r / (r²+z²)
550    /// ∂θ_d/∂θ = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
551    /// ∂θ_d/∂x = (∂θ_d/∂θ) · (∂θ/∂x)
552    /// ∂θ_d/∂y = (∂θ_d/∂θ) · (∂θ/∂y)
553    /// ∂θ_d/∂z = (∂θ_d/∂θ) · (∂θ/∂z)
554    /// ```
555    ///
556    /// Derivatives of pixel coordinates (quotient + product rule):
557    ///
558    /// For u = fx · θ_d · (x/r) + cx:
559    /// ```text
560    /// ∂u/∂x = fx · [∂θ_d/∂x · (x/r) + θ_d · ∂(x/r)/∂x]
561    ///       = fx · [∂θ_d/∂x · (x/r) + θ_d · (1/r - x²/r³)]
562    ///
563    /// ∂u/∂y = fx · [∂θ_d/∂y · (x/r) + θ_d · (-x·y/r³)]
564    ///
565    /// ∂u/∂z = fx · [∂θ_d/∂z · (x/r)]
566    /// ```
567    ///
568    /// Similarly for v = fy · θ_d · (y/r) + cy:
569    /// ```text
570    /// ∂v/∂x = fy · [∂θ_d/∂x · (y/r) + θ_d · (-x·y/r³)]
571    ///
572    /// ∂v/∂y = fy · [∂θ_d/∂y · (y/r) + θ_d · (1/r - y²/r³)]
573    ///
574    /// ∂v/∂z = fy · [∂θ_d/∂z · (y/r)]
575    /// ```
576    ///
577    /// Near optical axis (r → 0): Use simplified Jacobian for numerical stability:
578    /// ```text
579    /// ∂u/∂x ≈ fx · (∂θ_d/∂θ) / z
580    /// ∂v/∂y ≈ fy · (∂θ_d/∂θ) / z
581    /// (all other terms ≈ 0)
582    /// ```
583    ///
584    /// Final Jacobian matrix (2×3):
585    ///
586    /// ```text
587    /// J = [ ∂u/∂x  ∂u/∂y  ∂u/∂z ]
588    ///     [ ∂v/∂x  ∂v/∂y  ∂v/∂z ]
589    /// ```
590    ///
591    /// # Arguments
592    ///
593    /// * `p_cam` - 3D point in camera coordinate frame.
594    ///
595    /// # Returns
596    ///
597    /// Returns the 2×3 Jacobian matrix.
598    ///
599    /// # References
600    ///
601    /// - Kannala & Brandt, "A Generic Camera Model and Calibration Method for Conventional,
602    ///   Wide-Angle, and Fish-Eye Lenses", IEEE PAMI 2006
603    /// - Verified against numerical differentiation in `test_jacobian_point_numerical()`
604    ///
605    /// # Implementation Note
606    ///
607    /// The implementation handles the optical axis singularity (r → 0) using a threshold check
608    /// and falls back to a simplified Jacobian for numerical stability.
609    fn jacobian_point(&self, p_cam: &Vector3<f64>) -> Self::PointJacobian {
610        let x = p_cam[0];
611        let y = p_cam[1];
612        let z = p_cam[2];
613
614        let (k1, k2, k3, k4) = self.distortion_params();
615        let r = (x * x + y * y).sqrt();
616        let theta = r.atan2(z);
617
618        let theta2 = theta * theta;
619        let theta3 = theta2 * theta;
620        let theta5 = theta3 * theta2;
621        let theta7 = theta5 * theta2;
622        let theta9 = theta7 * theta2;
623
624        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
625
626        // ∂θ_d/∂θ = 1 + 3k₁·θ² + 5k₂·θ⁴ + 7k₃·θ⁶ + 9k₄·θ⁸
627        let dtheta_d_dtheta = 1.0
628            + 3.0 * k1 * theta2
629            + 5.0 * k2 * theta2 * theta2
630            + 7.0 * k3 * theta2 * theta2 * theta2
631            + 9.0 * k4 * theta2 * theta2 * theta2 * theta2;
632
633        if r < crate::GEOMETRIC_PRECISION {
634            // Near optical axis, use simplified Jacobian
635            return SMatrix::<f64, 2, 3>::new(
636                self.pinhole.fx * dtheta_d_dtheta / z,
637                0.0,
638                0.0,
639                0.0,
640                self.pinhole.fy * dtheta_d_dtheta / z,
641                0.0,
642            );
643        }
644
645        let inv_r = 1.0 / r;
646        let r2 = r * r;
647        let r_z2 = r2 + z * z;
648
649        // ∂θ/∂x = z·x / (r·(r² + z²))
650        // ∂θ/∂y = z·y / (r·(r² + z²))
651        // ∂θ/∂z = -r / (r² + z²)
652        let dtheta_dx = z * x / (r * r_z2);
653        let dtheta_dy = z * y / (r * r_z2);
654        let dtheta_dz = -r / r_z2;
655
656        // ∂r/∂x = x/r, ∂r/∂y = y/r, ∂r/∂z = 0
657
658        // Chain rule for u = fx · θ_d · (x/r) + cx
659        let inv_r2 = inv_r * inv_r;
660
661        let du_dx = self.pinhole.fx
662            * (dtheta_d_dtheta * dtheta_dx * x * inv_r
663                + theta_d * (inv_r - x * x * inv_r2 * inv_r));
664        let du_dy = self.pinhole.fx
665            * (dtheta_d_dtheta * dtheta_dy * x * inv_r - theta_d * x * y * inv_r2 * inv_r);
666        let du_dz = self.pinhole.fx * dtheta_d_dtheta * dtheta_dz * x * inv_r;
667
668        let dv_dx = self.pinhole.fy
669            * (dtheta_d_dtheta * dtheta_dx * y * inv_r - theta_d * x * y * inv_r2 * inv_r);
670        let dv_dy = self.pinhole.fy
671            * (dtheta_d_dtheta * dtheta_dy * y * inv_r
672                + theta_d * (inv_r - y * y * inv_r2 * inv_r));
673        let dv_dz = self.pinhole.fy * dtheta_d_dtheta * dtheta_dz * y * inv_r;
674
675        SMatrix::<f64, 2, 3>::new(du_dx, du_dy, du_dz, dv_dx, dv_dy, dv_dz)
676    }
677
678    /// Jacobian of projection w.r.t. intrinsic parameters (2×8).
679    ///
680    /// Computes ∂π/∂K where K = [fx, fy, cx, cy, k₁, k₂, k₃, k₄] are the intrinsic parameters.
681    ///
682    /// # Mathematical Derivation
683    ///
684    /// The intrinsic parameters consist of:
685    /// 1. **Linear parameters**: fx, fy, cx, cy (pinhole projection)
686    /// 2. **Distortion parameters**: k₁, k₂, k₃, k₄ (Kannala-Brandt polynomial coefficients)
687    ///
688    /// ## Kannala-Brandt Projection Model Recap
689    ///
690    /// ```text
691    /// r = √(x² + y²)
692    /// θ = atan2(r, z)
693    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
694    /// u = fx · θ_d · (x/r) + cx
695    /// v = fy · θ_d · (y/r) + cy
696    /// ```
697    ///
698    /// Linear parameters (fx, fy, cx, cy):
699    /// ```text
700    /// ∂u/∂fx = θ_d · (x/r),  ∂u/∂fy = 0,  ∂u/∂cx = 1,  ∂u/∂cy = 0
701    /// ∂v/∂fx = 0,  ∂v/∂fy = θ_d · (y/r),  ∂v/∂cx = 0,  ∂v/∂cy = 1
702    /// ```
703    ///
704    /// Distortion parameters (k₁, k₂, k₃, k₄):
705    ///
706    /// The distortion affects θ_d through the polynomial expansion.
707    ///
708    /// ### Derivatives of θ_d:
709    /// ```text
710    /// θ_d = θ + k₁·θ³ + k₂·θ⁵ + k₃·θ⁷ + k₄·θ⁹
711    ///
712    /// ∂θ_d/∂k₁ = θ³
713    /// ∂θ_d/∂k₂ = θ⁵
714    /// ∂θ_d/∂k₃ = θ⁷
715    /// ∂θ_d/∂k₄ = θ⁹
716    /// ```
717    ///
718    /// ### Chain rule to pixel coordinates:
719    ///
720    /// For u = fx · θ_d · (x/r) + cx:
721    /// ```text
722    /// ∂u/∂k₁ = fx · (∂θ_d/∂k₁) · (x/r) = fx · θ³ · (x/r)
723    /// ∂u/∂k₂ = fx · θ⁵ · (x/r)
724    /// ∂u/∂k₃ = fx · θ⁷ · (x/r)
725    /// ∂u/∂k₄ = fx · θ⁹ · (x/r)
726    /// ```
727    ///
728    /// Similarly for v = fy · θ_d · (y/r) + cy:
729    /// ```text
730    /// ∂v/∂k₁ = fy · θ³ · (y/r)
731    /// ∂v/∂k₂ = fy · θ⁵ · (y/r)
732    /// ∂v/∂k₃ = fy · θ⁷ · (y/r)
733    /// ∂v/∂k₄ = fy · θ⁹ · (y/r)
734    /// ```
735    ///
736    /// ## Final Jacobian Matrix (2×8)
737    ///
738    /// ```text
739    /// J = [ ∂u/∂fx  ∂u/∂fy  ∂u/∂cx  ∂u/∂cy  ∂u/∂k₁  ∂u/∂k₂  ∂u/∂k₃  ∂u/∂k₄ ]
740    ///     [ ∂v/∂fx  ∂v/∂fy  ∂v/∂cx  ∂v/∂cy  ∂v/∂k₁  ∂v/∂k₂  ∂v/∂k₃  ∂v/∂k₄ ]
741    /// ```
742    ///
743    /// Expanded:
744    /// ```text
745    /// J = [ θ_d·x/r    0       1    0    fx·θ³·x/r  fx·θ⁵·x/r  fx·θ⁷·x/r  fx·θ⁹·x/r ]
746    ///     [    0    θ_d·y/r    0    1    fy·θ³·y/r  fy·θ⁵·y/r  fy·θ⁷·y/r  fy·θ⁹·y/r ]
747    /// ```
748    ///
749    /// # Arguments
750    ///
751    /// * `p_cam` - 3D point in camera coordinate frame.
752    ///
753    /// # Returns
754    ///
755    /// Returns the 2×8 intrinsic Jacobian matrix.
756    ///
757    /// # References
758    ///
759    /// - Kannala & Brandt, "A Generic Camera Model and Calibration Method for Conventional,
760    ///   Wide-Angle, and Fish-Eye Lenses", IEEE PAMI 2006
761    /// - Verified against numerical differentiation in `test_jacobian_intrinsics_numerical()`
762    ///
763    /// # Implementation Note
764    ///
765    /// For numerical stability, when r (radial distance) is very small (near optical axis),
766    /// the Jacobian is set to zero as the projection becomes degenerate in this region.
767    fn jacobian_intrinsics(&self, p_cam: &Vector3<f64>) -> Self::IntrinsicJacobian {
768        let x = p_cam[0];
769        let y = p_cam[1];
770        let z = p_cam[2];
771
772        let (k1, k2, k3, k4) = self.distortion_params();
773        let r = (x * x + y * y).sqrt();
774        let theta = r.atan2(z);
775
776        let theta2 = theta * theta;
777        let theta3 = theta2 * theta;
778        let theta5 = theta3 * theta2;
779        let theta7 = theta5 * theta2;
780        let theta9 = theta7 * theta2;
781
782        let theta_d = theta + k1 * theta3 + k2 * theta5 + k3 * theta7 + k4 * theta9;
783
784        if r < crate::GEOMETRIC_PRECISION {
785            return SMatrix::<f64, 2, 8>::zeros();
786        }
787
788        let inv_r = 1.0 / r;
789        let x_theta_d_r = x * theta_d * inv_r;
790        let y_theta_d_r = y * theta_d * inv_r;
791
792        // ∂u/∂fx = θ_d·x/r, ∂u/∂fy = 0, ∂u/∂cx = 1, ∂u/∂cy = 0
793        // ∂v/∂fx = 0, ∂v/∂fy = θ_d·y/r, ∂v/∂cx = 0, ∂v/∂cy = 1
794
795        // ∂u/∂k₁ = fx·θ³·x/r, ∂u/∂k₂ = fx·θ⁵·x/r, etc.
796        let du_dk1 = self.pinhole.fx * theta3 * x * inv_r;
797        let du_dk2 = self.pinhole.fx * theta5 * x * inv_r;
798        let du_dk3 = self.pinhole.fx * theta7 * x * inv_r;
799        let du_dk4 = self.pinhole.fx * theta9 * x * inv_r;
800
801        let dv_dk1 = self.pinhole.fy * theta3 * y * inv_r;
802        let dv_dk2 = self.pinhole.fy * theta5 * y * inv_r;
803        let dv_dk3 = self.pinhole.fy * theta7 * y * inv_r;
804        let dv_dk4 = self.pinhole.fy * theta9 * y * inv_r;
805
806        SMatrix::<f64, 2, 8>::from_row_slice(&[
807            x_theta_d_r,
808            0.0,
809            1.0,
810            0.0,
811            du_dk1,
812            du_dk2,
813            du_dk3,
814            du_dk4,
815            0.0,
816            y_theta_d_r,
817            0.0,
818            1.0,
819            dv_dk1,
820            dv_dk2,
821            dv_dk3,
822            dv_dk4,
823        ])
824    }
825
826    /// Validates camera parameters.
827    ///
828    /// # Validation Rules
829    ///
830    /// - `fx`, `fy` must be positive.
831    /// - `fx`, `fy` must be finite.
832    /// - `cx`, `cy` must be finite.
833    /// - `k1`..`k4` must be finite.
834    ///
835    /// # Errors
836    ///
837    /// Returns [`CameraModelError`] if any parameter violates validation rules.
838    fn validate_params(&self) -> Result<(), CameraModelError> {
839        self.pinhole.validate()?;
840        self.get_distortion().validate()
841    }
842
843    /// Returns the pinhole parameters of the camera.
844    ///
845    /// # Returns
846    ///
847    /// A [`PinholeParams`] struct containing the focal lengths (fx, fy) and principal point (cx, cy).
848    fn get_pinhole_params(&self) -> PinholeParams {
849        PinholeParams {
850            fx: self.pinhole.fx,
851            fy: self.pinhole.fy,
852            cx: self.pinhole.cx,
853            cy: self.pinhole.cy,
854        }
855    }
856
857    /// Returns the distortion model and parameters of the camera.
858    ///
859    /// # Returns
860    ///
861    /// The [`DistortionModel`] associated with this camera (typically [`DistortionModel::KannalaBrandt`]).
862    fn get_distortion(&self) -> DistortionModel {
863        self.distortion
864    }
865
866    /// Returns the string identifier for the camera model.
867    ///
868    /// # Returns
869    ///
870    /// The string `"kannala_brandt"`.
871    fn get_model_name(&self) -> &'static str {
872        "kannala_brandt"
873    }
874}
875
876#[cfg(test)]
877mod tests {
878    use super::*;
879    use nalgebra::{Matrix2xX, Matrix3xX};
880
881    type TestResult = Result<(), Box<dyn std::error::Error>>;
882
883    #[test]
884    fn test_kb_camera_creation() -> TestResult {
885        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
886        let distortion = DistortionModel::KannalaBrandt {
887            k1: 0.1,
888            k2: 0.01,
889            k3: 0.001,
890            k4: 0.0001,
891        };
892        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
893        assert_eq!(camera.pinhole.fx, 300.0);
894        let (k1, _, _, _) = camera.distortion_params();
895        assert_eq!(k1, 0.1);
896        Ok(())
897    }
898
899    #[test]
900    fn test_projection_at_optical_axis() -> TestResult {
901        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
902        let distortion = DistortionModel::KannalaBrandt {
903            k1: 0.1,
904            k2: 0.01,
905            k3: 0.001,
906            k4: 0.0001,
907        };
908        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
909        let p_cam = Vector3::new(0.0, 0.0, 1.0);
910        let uv = camera.project(&p_cam)?;
911
912        assert!((uv.x - 320.0).abs() < 1e-6);
913        assert!((uv.y - 240.0).abs() < 1e-6);
914
915        Ok(())
916    }
917
918    #[test]
919    fn test_jacobian_point_numerical() -> TestResult {
920        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
921        let distortion = DistortionModel::KannalaBrandt {
922            k1: 0.1,
923            k2: 0.01,
924            k3: 0.001,
925            k4: 0.0001,
926        };
927        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
928        let p_cam = Vector3::new(0.1, 0.2, 1.0);
929
930        let jac_analytical = camera.jacobian_point(&p_cam);
931        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
932
933        for i in 0..3 {
934            let mut p_plus = p_cam;
935            let mut p_minus = p_cam;
936            p_plus[i] += eps;
937            p_minus[i] -= eps;
938
939            let uv_plus = camera.project(&p_plus)?;
940            let uv_minus = camera.project(&p_minus)?;
941            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
942
943            for r in 0..2 {
944                assert!(
945                    jac_analytical[(r, i)].is_finite(),
946                    "Jacobian [{r},{i}] is not finite"
947                );
948                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
949                assert!(
950                    diff < crate::JACOBIAN_TEST_TOLERANCE,
951                    "Mismatch at ({}, {})",
952                    r,
953                    i
954                );
955            }
956        }
957        Ok(())
958    }
959
960    #[test]
961    fn test_jacobian_intrinsics_numerical() -> TestResult {
962        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
963        let distortion = DistortionModel::KannalaBrandt {
964            k1: 0.1,
965            k2: 0.01,
966            k3: 0.001,
967            k4: 0.0001,
968        };
969        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
970        let p_cam = Vector3::new(0.1, 0.2, 1.0);
971
972        let jac_analytical = camera.jacobian_intrinsics(&p_cam);
973        let params: DVector<f64> = (&camera).into();
974        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
975
976        for i in 0..8 {
977            let mut params_plus = params.clone();
978            let mut params_minus = params.clone();
979            params_plus[i] += eps;
980            params_minus[i] -= eps;
981
982            let cam_plus = KannalaBrandtCamera::try_from(params_plus.as_slice())?;
983            let cam_minus = KannalaBrandtCamera::try_from(params_minus.as_slice())?;
984
985            let uv_plus = cam_plus.project(&p_cam)?;
986            let uv_minus = cam_minus.project(&p_cam)?;
987            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
988
989            for r in 0..2 {
990                assert!(
991                    jac_analytical[(r, i)].is_finite(),
992                    "Jacobian [{r},{i}] is not finite"
993                );
994                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
995                assert!(
996                    diff < crate::JACOBIAN_TEST_TOLERANCE,
997                    "Mismatch at ({}, {})",
998                    r,
999                    i
1000                );
1001            }
1002        }
1003        Ok(())
1004    }
1005
1006    #[test]
1007    fn test_kb_from_into_traits() -> TestResult {
1008        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1009        let distortion = DistortionModel::KannalaBrandt {
1010            k1: 0.1,
1011            k2: 0.01,
1012            k3: 0.001,
1013            k4: 0.0001,
1014        };
1015        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1016
1017        // Test conversion to DVector
1018        let params: DVector<f64> = (&camera).into();
1019        assert_eq!(params.len(), 8);
1020        assert_eq!(params[0], 300.0);
1021        assert_eq!(params[1], 300.0);
1022        assert_eq!(params[2], 320.0);
1023        assert_eq!(params[3], 240.0);
1024        assert_eq!(params[4], 0.1);
1025        assert_eq!(params[5], 0.01);
1026        assert_eq!(params[6], 0.001);
1027        assert_eq!(params[7], 0.0001);
1028
1029        // Test conversion to array
1030        let arr: [f64; 8] = (&camera).into();
1031        assert_eq!(arr, [300.0, 300.0, 320.0, 240.0, 0.1, 0.01, 0.001, 0.0001]);
1032
1033        // Test conversion from slice
1034        let params_slice = [350.0, 350.0, 330.0, 250.0, 0.2, 0.02, 0.002, 0.0002];
1035        let camera2 = KannalaBrandtCamera::try_from(&params_slice[..])?;
1036        assert_eq!(camera2.pinhole.fx, 350.0);
1037        assert_eq!(camera2.pinhole.fy, 350.0);
1038        assert_eq!(camera2.pinhole.cx, 330.0);
1039        assert_eq!(camera2.pinhole.cy, 250.0);
1040        let (k1, k2, k3, k4) = camera2.distortion_params();
1041        assert_eq!(k1, 0.2);
1042        assert_eq!(k2, 0.02);
1043        assert_eq!(k3, 0.002);
1044        assert_eq!(k4, 0.0002);
1045
1046        // Test conversion from array
1047        let camera3 =
1048            KannalaBrandtCamera::from([400.0, 400.0, 340.0, 260.0, 0.3, 0.03, 0.003, 0.0003]);
1049        assert_eq!(camera3.pinhole.fx, 400.0);
1050        assert_eq!(camera3.pinhole.fy, 400.0);
1051        let (k1, k2, k3, k4) = camera3.distortion_params();
1052        assert_eq!(k1, 0.3);
1053        assert_eq!(k2, 0.03);
1054        assert_eq!(k3, 0.003);
1055        assert_eq!(k4, 0.0003);
1056
1057        Ok(())
1058    }
1059
1060    #[test]
1061    fn test_linear_estimation() -> TestResult {
1062        // Ground truth fisheye camera
1063        let gt_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1064        let gt_distortion = DistortionModel::KannalaBrandt {
1065            k1: 0.1,
1066            k2: 0.01,
1067            k3: 0.001,
1068            k4: 0.0001,
1069        };
1070        let gt_camera = KannalaBrandtCamera::new(gt_pinhole, gt_distortion)?;
1071
1072        // Generate synthetic 3D points in camera frame
1073        let n_points = 50;
1074        let mut pts_3d = Matrix3xX::zeros(n_points);
1075        let mut pts_2d = Matrix2xX::zeros(n_points);
1076        let mut valid = 0;
1077
1078        for i in 0..n_points {
1079            let angle = i as f64 * 2.0 * std::f64::consts::PI / n_points as f64;
1080            let r = 0.1 + 0.4 * (i as f64 / n_points as f64);
1081            let p3d = Vector3::new(r * angle.cos(), r * angle.sin(), 1.0);
1082
1083            if let Ok(p2d) = gt_camera.project(&p3d) {
1084                pts_3d.set_column(valid, &p3d);
1085                pts_2d.set_column(valid, &p2d);
1086                valid += 1;
1087            }
1088        }
1089        let pts_3d = pts_3d.columns(0, valid).into_owned();
1090        let pts_2d = pts_2d.columns(0, valid).into_owned();
1091
1092        // Initial camera with zero distortion
1093        let init_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1094        let init_distortion = DistortionModel::KannalaBrandt {
1095            k1: 0.0,
1096            k2: 0.0,
1097            k3: 0.0,
1098            k4: 0.0,
1099        };
1100        let mut camera = KannalaBrandtCamera::new(init_pinhole, init_distortion)?;
1101
1102        camera.linear_estimation(&pts_3d, &pts_2d)?;
1103
1104        // Verify reprojection error
1105        for i in 0..valid {
1106            let col = pts_3d.column(i);
1107            let projected = camera.project(&Vector3::new(col[0], col[1], col[2]))?;
1108            let err = ((projected.x - pts_2d[(0, i)]).powi(2)
1109                + (projected.y - pts_2d[(1, i)]).powi(2))
1110            .sqrt();
1111            assert!(err < 3.0, "Reprojection error too large: {err}");
1112        }
1113
1114        Ok(())
1115    }
1116
1117    #[test]
1118    fn test_project_unproject_round_trip() -> TestResult {
1119        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1120        let distortion = DistortionModel::KannalaBrandt {
1121            k1: 0.1,
1122            k2: 0.01,
1123            k3: 0.001,
1124            k4: 0.0001,
1125        };
1126        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1127
1128        let test_points = [
1129            Vector3::new(0.1, 0.2, 1.0),
1130            Vector3::new(-0.3, 0.1, 2.0),
1131            Vector3::new(0.05, -0.1, 0.5),
1132        ];
1133
1134        for p_cam in &test_points {
1135            let uv = camera.project(p_cam)?;
1136            let ray = camera.unproject(&uv)?;
1137            let dot = ray.dot(&p_cam.normalize());
1138            assert!(
1139                (dot - 1.0).abs() < 1e-6,
1140                "Round-trip failed: dot={dot}, expected ~1.0"
1141            );
1142        }
1143
1144        Ok(())
1145    }
1146
1147    #[test]
1148    fn test_project_returns_error_behind_camera() -> TestResult {
1149        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1150        let distortion = DistortionModel::KannalaBrandt {
1151            k1: 0.0,
1152            k2: 0.0,
1153            k3: 0.0,
1154            k4: 0.0,
1155        };
1156        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1157        assert!(camera.project(&Vector3::new(0.0, 0.0, -1.0)).is_err());
1158        Ok(())
1159    }
1160
1161    #[test]
1162    fn test_project_at_min_depth_boundary() -> TestResult {
1163        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1164        let distortion = DistortionModel::KannalaBrandt {
1165            k1: 0.0,
1166            k2: 0.0,
1167            k3: 0.0,
1168            k4: 0.0,
1169        };
1170        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1171        let p_min = Vector3::new(0.0, 0.0, crate::MIN_DEPTH);
1172        if let Ok(uv) = camera.project(&p_min) {
1173            assert!(uv.x.is_finite() && uv.y.is_finite());
1174        }
1175        Ok(())
1176    }
1177
1178    #[test]
1179    fn test_projection_off_axis() -> TestResult {
1180        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1181        let distortion = DistortionModel::KannalaBrandt {
1182            k1: 0.1,
1183            k2: 0.01,
1184            k3: 0.001,
1185            k4: 0.0001,
1186        };
1187        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1188        let p_cam = Vector3::new(0.3, 0.0, 1.0);
1189        let uv = camera.project(&p_cam)?;
1190        assert!(
1191            uv.x > 320.0,
1192            "off-axis point should project right of principal point"
1193        );
1194        assert!(
1195            (uv.y - 240.0).abs() < 1.0,
1196            "y should be close to cy for horizontal offset"
1197        );
1198        Ok(())
1199    }
1200
1201    #[test]
1202    fn test_unproject_center_pixel() -> TestResult {
1203        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1204        let distortion = DistortionModel::KannalaBrandt {
1205            k1: 0.1,
1206            k2: 0.01,
1207            k3: 0.001,
1208            k4: 0.0001,
1209        };
1210        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1211        let uv = Vector2::new(320.0, 240.0);
1212        let ray = camera.unproject(&uv)?;
1213        assert!(ray.x.abs() < 1e-6, "x should be ~0, got {}", ray.x);
1214        assert!(ray.y.abs() < 1e-6, "y should be ~0, got {}", ray.y);
1215        assert!((ray.z - 1.0).abs() < 1e-6, "z should be ~1, got {}", ray.z);
1216        Ok(())
1217    }
1218
1219    #[test]
1220    fn test_batch_projection_matches_individual() -> TestResult {
1221        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1222        let distortion = DistortionModel::KannalaBrandt {
1223            k1: 0.1,
1224            k2: 0.01,
1225            k3: 0.001,
1226            k4: 0.0001,
1227        };
1228        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1229        let pts = Matrix3xX::from_columns(&[
1230            Vector3::new(0.0, 0.0, 1.0),
1231            Vector3::new(0.3, 0.2, 1.5),
1232            Vector3::new(-0.4, 0.1, 2.0),
1233        ]);
1234        let batch = camera.project_batch(&pts);
1235        for i in 0..3 {
1236            let col = pts.column(i);
1237            let p = camera.project(&Vector3::new(col[0], col[1], col[2]))?;
1238            assert!(
1239                (batch[(0, i)] - p.x).abs() < 1e-10,
1240                "batch u mismatch at col {i}"
1241            );
1242            assert!(
1243                (batch[(1, i)] - p.y).abs() < 1e-10,
1244                "batch v mismatch at col {i}"
1245            );
1246        }
1247        Ok(())
1248    }
1249
1250    #[test]
1251    fn test_jacobian_dimensions() -> TestResult {
1252        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1253        let distortion = DistortionModel::KannalaBrandt {
1254            k1: 0.1,
1255            k2: 0.01,
1256            k3: 0.001,
1257            k4: 0.0001,
1258        };
1259        let camera = KannalaBrandtCamera::new(pinhole, distortion)?;
1260        let p_cam = Vector3::new(0.1, 0.2, 1.0);
1261        let jac_point = camera.jacobian_point(&p_cam);
1262        assert_eq!(jac_point.nrows(), 2);
1263        assert_eq!(jac_point.ncols(), 3);
1264        let jac_intr = camera.jacobian_intrinsics(&p_cam);
1265        assert_eq!(jac_intr.nrows(), 2);
1266        assert_eq!(jac_intr.ncols(), 8); // KannalaBrandtCamera::INTRINSIC_DIM = 8
1267        Ok(())
1268    }
1269}