Skip to main content

apex_camera_models/
rad_tan.rs

1//! Radial-Tangential Distortion Camera Model.
2//!
3//! The standard OpenCV camera model combining radial and tangential distortion.
4//! This model is widely used for narrow to moderate field-of-view cameras.
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//! x' = x/z,  y' = y/z  (normalized coordinates)
14//! r² = x'² + y'²
15//!
16//! Radial distortion:
17//! r' = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
18//!
19//! Tangential distortion:
20//! dx = 2·p₁·x'·y' + p₂·(r² + 2·x'²)
21//! dy = p₁·(r² + 2·y'²) + 2·p₂·x'·y'
22//!
23//! Distorted coordinates:
24//! x'' = r'·x' + dx
25//! y'' = r'·y' + dy
26//!
27//! Final projection:
28//! u = fx·x'' + cx
29//! v = fy·y'' + cy
30//! ```
31//!
32//! ## Unprojection (2D → 3D)
33//!
34//! Iterative Jacobian-based method to solve the non-linear inverse equations.
35//!
36//! # Parameters
37//!
38//! - **Intrinsics**: fx, fy, cx, cy
39//! - **Distortion**: k₁, k₂, p₁, p₂, k₃ (9 parameters total)
40//!
41//! # Use Cases
42//!
43//! - Standard narrow FOV cameras
44//! - OpenCV-calibrated cameras
45//! - Robotics and AR/VR applications
46//! - Most conventional lenses
47//!
48//! # References
49//!
50//! - Brown, "Decentering Distortion of Lenses", 1966
51//! - OpenCV Camera Calibration Documentation
52
53use crate::{CameraModel, CameraModelError, DistortionModel, PinholeParams};
54use nalgebra::{DVector, Matrix2, SMatrix, Vector2, Vector3};
55
56/// A Radial-Tangential camera model with 9 intrinsic parameters.
57#[derive(Debug, Clone, Copy, PartialEq)]
58pub struct RadTanCamera {
59    pub pinhole: PinholeParams,
60    pub distortion: DistortionModel,
61}
62
63impl RadTanCamera {
64    /// Creates a new Radial-Tangential (Brown-Conrady) camera.
65    ///
66    /// # Arguments
67    ///
68    /// * `pinhole` - The pinhole parameters (fx, fy, cx, cy).
69    /// * `distortion` - The distortion model. This must be `DistortionModel::BrownConrady` with parameters { k1, k2, p1, p2, k3 }.
70    ///
71    /// # Errors
72    ///
73    /// Returns [`CameraModelError::InvalidParams`] if `distortion` is not [`DistortionModel::BrownConrady`].
74    pub fn new(
75        pinhole: PinholeParams,
76        distortion: DistortionModel,
77    ) -> Result<Self, CameraModelError> {
78        let camera = Self {
79            pinhole,
80            distortion,
81        };
82        camera.validate_params()?;
83        Ok(camera)
84    }
85
86    /// Checks if a 3D point satisfies the projection condition.
87    ///
88    /// # Arguments
89    ///
90    /// * `z` - The z-coordinate of the point in the camera frame.
91    ///
92    /// # Returns
93    ///
94    /// Returns `true` if `z >= crate::GEOMETRIC_PRECISION`, `false` otherwise.
95    fn check_projection_condition(&self, z: f64) -> bool {
96        z >= crate::GEOMETRIC_PRECISION
97    }
98
99    /// Helper method to extract distortion parameters.
100    ///
101    /// # Returns
102    ///
103    /// Returns a tuple `(k1, k2, p1, p2, k3)` containing the Brown-Conrady distortion parameters.
104    /// If the distortion model is not Brown-Conrady, returns `(0.0, 0.0, 0.0, 0.0, 0.0)`.
105    fn distortion_params(&self) -> (f64, f64, f64, f64, f64) {
106        match self.distortion {
107            DistortionModel::BrownConrady { k1, k2, p1, p2, k3 } => (k1, k2, p1, p2, k3),
108            _ => (0.0, 0.0, 0.0, 0.0, 0.0),
109        }
110    }
111
112    /// Performs linear estimation to initialize distortion parameters from point correspondences.
113    ///
114    /// This method estimates the radial distortion coefficients [k1, k2, k3] using a linear
115    /// least squares approach given 3D-2D point correspondences. Tangential distortion parameters
116    /// (p1, p2) are set to 0.0. It assumes the intrinsic parameters (fx, fy, cx, cy) are already set.
117    ///
118    /// # Arguments
119    ///
120    /// * `points_3d`: Matrix3xX<f64> - 3D points in camera coordinates (each column is a point)
121    /// * `points_2d`: Matrix2xX<f64> - Corresponding 2D points in image coordinates
122    ///
123    /// # Returns
124    ///
125    /// Returns `Ok(())` on success or a `CameraModelError` if the estimation fails.
126    pub fn linear_estimation(
127        &mut self,
128        points_3d: &nalgebra::Matrix3xX<f64>,
129        points_2d: &nalgebra::Matrix2xX<f64>,
130    ) -> Result<(), CameraModelError> {
131        if points_2d.ncols() != points_3d.ncols() {
132            return Err(CameraModelError::InvalidParams(
133                "Number of 2D and 3D points must match".to_string(),
134            ));
135        }
136
137        let num_points = points_2d.ncols();
138        if num_points < 3 {
139            return Err(CameraModelError::InvalidParams(
140                "Need at least 3 points for RadTan linear estimation".to_string(),
141            ));
142        }
143
144        // Set up the linear system to estimate distortion coefficients
145        let mut a = nalgebra::DMatrix::zeros(num_points * 2, 3); // Only estimate k1, k2, k3
146        let mut b = nalgebra::DVector::zeros(num_points * 2);
147
148        // Extract intrinsics
149        let fx = self.pinhole.fx;
150        let fy = self.pinhole.fy;
151        let cx = self.pinhole.cx;
152        let cy = self.pinhole.cy;
153
154        for i in 0..num_points {
155            let x = points_3d[(0, i)];
156            let y = points_3d[(1, i)];
157            let z = points_3d[(2, i)];
158            let u = points_2d[(0, i)];
159            let v = points_2d[(1, i)];
160
161            // Project to normalized coordinates
162            let x_norm = x / z;
163            let y_norm = y / z;
164            let r2 = x_norm * x_norm + y_norm * y_norm;
165            let r4 = r2 * r2;
166            let r6 = r4 * r2;
167
168            // Predicted undistorted pixel coordinates
169            let u_undist = fx * x_norm + cx;
170            let v_undist = fy * y_norm + cy;
171
172            // Set up linear system for distortion coefficients
173            a[(i * 2, 0)] = fx * x_norm * r2; // k1 term
174            a[(i * 2, 1)] = fx * x_norm * r4; // k2 term
175            a[(i * 2, 2)] = fx * x_norm * r6; // k3 term
176
177            a[(i * 2 + 1, 0)] = fy * y_norm * r2; // k1 term
178            a[(i * 2 + 1, 1)] = fy * y_norm * r4; // k2 term
179            a[(i * 2 + 1, 2)] = fy * y_norm * r6; // k3 term
180
181            b[i * 2] = u - u_undist;
182            b[i * 2 + 1] = v - v_undist;
183        }
184
185        // Solve the linear system using SVD
186        let svd = a.svd(true, true);
187        let distortion_coeffs = match svd.solve(&b, 1e-10) {
188            Ok(sol) => sol,
189            Err(err_msg) => {
190                return Err(CameraModelError::NumericalError {
191                    operation: "svd_solve".to_string(),
192                    details: err_msg.to_string(),
193                });
194            }
195        };
196
197        // Update distortion coefficients (keep p1, p2 as zero for linear estimation)
198        self.distortion = DistortionModel::BrownConrady {
199            k1: distortion_coeffs[0],
200            k2: distortion_coeffs[1],
201            p1: 0.0,
202            p2: 0.0,
203            k3: distortion_coeffs[2],
204        };
205
206        self.validate_params()?;
207        Ok(())
208    }
209}
210
211/// Converts the camera parameters to a dynamic vector.
212///
213/// # Layout
214///
215/// The parameters are ordered as: `[fx, fy, cx, cy, k1, k2, p1, p2, k3]`
216impl From<&RadTanCamera> for DVector<f64> {
217    fn from(camera: &RadTanCamera) -> Self {
218        let (k1, k2, p1, p2, k3) = camera.distortion_params();
219        DVector::from_vec(vec![
220            camera.pinhole.fx,
221            camera.pinhole.fy,
222            camera.pinhole.cx,
223            camera.pinhole.cy,
224            k1,
225            k2,
226            p1,
227            p2,
228            k3,
229        ])
230    }
231}
232
233/// Converts the camera parameters to a fixed-size array.
234///
235/// # Layout
236///
237/// The parameters are ordered as: `[fx, fy, cx, cy, k1, k2, p1, p2, k3]`
238impl From<&RadTanCamera> for [f64; 9] {
239    fn from(camera: &RadTanCamera) -> Self {
240        let (k1, k2, p1, p2, k3) = camera.distortion_params();
241        [
242            camera.pinhole.fx,
243            camera.pinhole.fy,
244            camera.pinhole.cx,
245            camera.pinhole.cy,
246            k1,
247            k2,
248            p1,
249            p2,
250            k3,
251        ]
252    }
253}
254
255/// Creates a camera from a slice of intrinsic parameters.
256///
257/// # Layout
258///
259/// Expected parameter order: `[fx, fy, cx, cy, k1, k2, p1, p2, k3]`
260///
261/// # Panics
262///
263/// Panics if the slice has fewer than 9 elements.
264impl TryFrom<&[f64]> for RadTanCamera {
265    type Error = CameraModelError;
266
267    fn try_from(params: &[f64]) -> Result<Self, Self::Error> {
268        if params.len() < 9 {
269            return Err(CameraModelError::InvalidParams(format!(
270                "RadTanCamera requires at least 9 parameters, got {}",
271                params.len()
272            )));
273        }
274        Ok(Self {
275            pinhole: PinholeParams {
276                fx: params[0],
277                fy: params[1],
278                cx: params[2],
279                cy: params[3],
280            },
281            distortion: DistortionModel::BrownConrady {
282                k1: params[4],
283                k2: params[5],
284                p1: params[6],
285                p2: params[7],
286                k3: params[8],
287            },
288        })
289    }
290}
291
292/// Creates a camera from a fixed-size array of intrinsic parameters.
293///
294/// # Layout
295///
296/// Expected parameter order: `[fx, fy, cx, cy, k1, k2, p1, p2, k3]`
297impl From<[f64; 9]> for RadTanCamera {
298    fn from(params: [f64; 9]) -> Self {
299        Self {
300            pinhole: PinholeParams {
301                fx: params[0],
302                fy: params[1],
303                cx: params[2],
304                cy: params[3],
305            },
306            distortion: DistortionModel::BrownConrady {
307                k1: params[4],
308                k2: params[5],
309                p1: params[6],
310                p2: params[7],
311                k3: params[8],
312            },
313        }
314    }
315}
316
317/// Creates a `RadTanCamera` from a parameter slice with validation.
318///
319/// Unlike `From<&[f64]>`, this constructor validates all parameters
320/// and returns a `Result` instead of panicking on invalid input.
321///
322/// # Errors
323///
324/// Returns `CameraModelError::InvalidParams` if fewer than 9 parameters are provided.
325/// Returns validation errors if focal lengths are non-positive or parameters are non-finite.
326pub fn try_from_params(params: &[f64]) -> Result<RadTanCamera, CameraModelError> {
327    let camera = RadTanCamera::try_from(params)?;
328    camera.validate_params()?;
329    Ok(camera)
330}
331
332impl CameraModel for RadTanCamera {
333    const INTRINSIC_DIM: usize = 9;
334    type IntrinsicJacobian = SMatrix<f64, 2, 9>;
335    type PointJacobian = SMatrix<f64, 2, 3>;
336
337    /// Projects a 3D point in the camera frame to 2D image coordinates.
338    ///
339    /// # Mathematical Formula
340    ///
341    /// Combines radial distortion (k₁, k₂, k₃) and tangential distortion (p₁, p₂).
342    ///
343    /// # Arguments
344    ///
345    /// * `p_cam` - The 3D point in the camera coordinate frame.
346    ///
347    /// # Returns
348    ///
349    /// - `Ok(uv)` - The 2D image coordinates if valid.
350    /// - `Err` - If the point is at or behind the camera.
351    fn project(&self, p_cam: &Vector3<f64>) -> Result<Vector2<f64>, CameraModelError> {
352        if !self.check_projection_condition(p_cam.z) {
353            return Err(CameraModelError::PointBehindCamera {
354                z: p_cam.z,
355                min_z: crate::GEOMETRIC_PRECISION,
356            });
357        }
358
359        let inv_z = 1.0 / p_cam.z;
360        let x_prime = p_cam.x * inv_z;
361        let y_prime = p_cam.y * inv_z;
362
363        let r2 = x_prime * x_prime + y_prime * y_prime;
364        let r4 = r2 * r2;
365        let r6 = r4 * r2;
366
367        let (k1, k2, p1, p2, k3) = self.distortion_params();
368
369        // Radial distortion: r' = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
370        let radial = 1.0 + k1 * r2 + k2 * r4 + k3 * r6;
371
372        // Tangential distortion
373        let xy = x_prime * y_prime;
374        let dx = 2.0 * p1 * xy + p2 * (r2 + 2.0 * x_prime * x_prime);
375        let dy = p1 * (r2 + 2.0 * y_prime * y_prime) + 2.0 * p2 * xy;
376
377        // Distorted coordinates
378        let x_distorted = radial * x_prime + dx;
379        let y_distorted = radial * y_prime + dy;
380
381        Ok(Vector2::new(
382            self.pinhole.fx * x_distorted + self.pinhole.cx,
383            self.pinhole.fy * y_distorted + self.pinhole.cy,
384        ))
385    }
386
387    /// Unprojects a 2D image point to a 3D ray.
388    ///
389    /// # Algorithm
390    ///
391    /// Iterative Newton-Raphson with Jacobian matrix:
392    /// 1. Start with the undistorted estimate.
393    /// 2. Compute distortion and Jacobian.
394    /// 3. Update estimate: p′ = p′ − J⁻¹ · f(p′).
395    /// 4. Repeat until convergence.
396    ///
397    /// # Arguments
398    ///
399    /// * `point_2d` - The 2D point in image coordinates.
400    ///
401    /// # Returns
402    ///
403    /// - `Ok(ray)` - The normalized 3D ray direction.
404    /// - `Err` - If the iteration fails to converge.
405    fn unproject(&self, point_2d: &Vector2<f64>) -> Result<Vector3<f64>, CameraModelError> {
406        // Validate unprojection condition if needed (always true for RadTan generally)
407        let u = point_2d.x;
408        let v = point_2d.y;
409
410        // Initial estimate (undistorted)
411        let x_distorted = (u - self.pinhole.cx) / self.pinhole.fx;
412        let y_distorted = (v - self.pinhole.cy) / self.pinhole.fy;
413        let target_distorted_point = Vector2::new(x_distorted, y_distorted);
414
415        let mut point = target_distorted_point;
416
417        const CONVERGENCE_EPS: f64 = crate::CONVERGENCE_THRESHOLD;
418        const MAX_ITERATIONS: u32 = 100;
419
420        let (k1, k2, p1, p2, k3) = self.distortion_params();
421
422        for iteration in 0..MAX_ITERATIONS {
423            let x = point.x;
424            let y = point.y;
425
426            let r2 = x * x + y * y;
427            let r4 = r2 * r2;
428            let r6 = r4 * r2;
429
430            // Radial distortion
431            let radial = 1.0 + k1 * r2 + k2 * r4 + k3 * r6;
432
433            // Tangential distortion
434            let xy = x * y;
435            let dx = 2.0 * p1 * xy + p2 * (r2 + 2.0 * x * x);
436            let dy = p1 * (r2 + 2.0 * y * y) + 2.0 * p2 * xy;
437
438            // Distorted point
439            let x_dist = radial * x + dx;
440            let y_dist = radial * y + dy;
441
442            // Residual
443            let fx = x_dist - target_distorted_point.x;
444            let fy = y_dist - target_distorted_point.y;
445
446            if fx.abs() < CONVERGENCE_EPS && fy.abs() < CONVERGENCE_EPS {
447                break;
448            }
449
450            // Jacobian matrix
451            let dradial_dr2 = k1 + 2.0 * k2 * r2 + 3.0 * k3 * r4;
452
453            // ∂(radial·x + dx)/∂x
454            let dfx_dx = radial + 2.0 * x * dradial_dr2 * x + 2.0 * p1 * y + 2.0 * p2 * (3.0 * x);
455
456            // ∂(radial·x + dx)/∂y
457            let dfx_dy = 2.0 * x * dradial_dr2 * y + 2.0 * p1 * x + 2.0 * p2 * y;
458
459            // ∂(radial·y + dy)/∂x
460            let dfy_dx = 2.0 * y * dradial_dr2 * x + 2.0 * p1 * x + 2.0 * p2 * y;
461
462            // ∂(radial·y + dy)/∂y
463            let dfy_dy = radial + 2.0 * y * dradial_dr2 * y + 2.0 * p1 * (3.0 * y) + 2.0 * p2 * x;
464
465            let jacobian = Matrix2::new(dfx_dx, dfx_dy, dfy_dx, dfy_dy);
466
467            // Solve: J·Δp = -f
468            let det = jacobian[(0, 0)] * jacobian[(1, 1)] - jacobian[(0, 1)] * jacobian[(1, 0)];
469
470            if det.abs() < crate::GEOMETRIC_PRECISION {
471                return Err(CameraModelError::NumericalError {
472                    operation: "unprojection".to_string(),
473                    details: "Singular Jacobian in RadTan unprojection".to_string(),
474                });
475            }
476
477            let inv_det = 1.0 / det;
478            let delta_x = inv_det * (jacobian[(1, 1)] * (-fx) - jacobian[(0, 1)] * (-fy));
479            let delta_y = inv_det * (-jacobian[(1, 0)] * (-fx) + jacobian[(0, 0)] * (-fy));
480
481            point.x += delta_x;
482            point.y += delta_y;
483
484            if iteration == MAX_ITERATIONS - 1 {
485                return Err(CameraModelError::NumericalError {
486                    operation: "unprojection".to_string(),
487                    details: "RadTan unprojection did not converge".to_string(),
488                });
489            }
490        }
491
492        // Normalize to unit ray
493        let r2 = point.x * point.x + point.y * point.y;
494        let norm = (1.0 + r2).sqrt();
495        let norm_inv = 1.0 / norm;
496
497        Ok(Vector3::new(
498            point.x * norm_inv,
499            point.y * norm_inv,
500            norm_inv,
501        ))
502    }
503
504    /// Computes the Jacobian of the projection with respect to the 3D point coordinates (2×3).
505    ///
506    /// # Mathematical Derivation
507    ///
508    /// For the Radial-Tangential (Brown-Conrady) model, projection is:
509    ///
510    /// ```text
511    /// x' = x/z,  y' = y/z  (normalized coordinates)
512    /// r² = x'² + y'²
513    /// radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
514    /// dx = 2·p₁·x'·y' + p₂·(r² + 2·x'²)  (tangential distortion)
515    /// dy = p₁·(r² + 2·y'²) + 2·p₂·x'·y'  (tangential distortion)
516    /// x'' = radial·x' + dx
517    /// y'' = radial·y' + dy
518    /// u = fx·x'' + cx
519    /// v = fy·y'' + cy
520    /// ```
521    ///
522    /// ## Chain Rule Application
523    ///
524    /// This is the most complex Jacobian due to coupled radial + tangential distortion.
525    /// The chain rule must be applied through multiple stages:
526    ///
527    /// 1. ∂(x',y')/∂(x,y,z): Normalized coordinate derivatives
528    /// 2. ∂(x'',y'')/∂(x',y'): Distortion derivatives (radial + tangential)
529    /// 3. ∂(u,v)/∂(x'',y''): Final projection derivatives
530    ///
531    /// Normalized coordinate derivatives (x' = x/z, y' = y/z):
532    /// ```text
533    /// ∂x'/∂x = 1/z,   ∂x'/∂y = 0,     ∂x'/∂z = -x/z²
534    /// ∂y'/∂x = 0,     ∂y'/∂y = 1/z,   ∂y'/∂z = -y/z²
535    /// ```
536    ///
537    /// Distortion derivatives:
538    ///
539    /// The distorted coordinates are: x'' = radial·x' + dx, y'' = radial·y' + dy
540    ///
541    /// #### Radial Distortion Component
542    ///
543    /// ```text
544    /// radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
545    /// ∂radial/∂r² = k₁ + 2k₂·r² + 3k₃·r⁴
546    /// ∂r²/∂x' = 2x',  ∂r²/∂y' = 2y'
547    /// ```
548    ///
549    /// #### Tangential Distortion Component
550    ///
551    /// For dx = 2p₁x'y' + p₂(r² + 2x'²):
552    ///
553    /// ```text
554    /// ∂dx/∂x' = 2p₁y' + p₂(2x' + 4x') = 2p₁y' + 6p₂x'
555    /// ∂dx/∂y' = 2p₁x' + 2p₂y'
556    /// ```
557    ///
558    /// For dy = p₁(r² + 2y'²) + 2p₂x'y':
559    ///
560    /// ```text
561    /// ∂dy/∂x' = 2p₁x' + 2p₂y'
562    /// ∂dy/∂y' = p₁(2y' + 4y') + 2p₂x' = 6p₁y' + 2p₂x'
563    /// ```
564    ///
565    /// #### Combined Distorted Coordinate Derivatives
566    ///
567    /// For x'' = radial·x' + dx:
568    ///
569    /// ```text
570    /// ∂x''/∂x' = radial + x'·∂radial/∂r²·∂r²/∂x' + ∂dx/∂x'
571    ///          = radial + x'·dradial_dr2·2x' + 2p₁y' + 6p₂x'
572    ///          = radial + 2x'²·dradial_dr2 + 2p₁y' + 6p₂x'
573    ///
574    /// ∂x''/∂y' = x'·∂radial/∂r²·∂r²/∂y' + ∂dx/∂y'
575    ///          = x'·dradial_dr2·2y' + 2p₁x' + 2p₂y'
576    ///          = 2x'y'·dradial_dr2 + 2p₁x' + 2p₂y'
577    /// ```
578    ///
579    /// For y'' = radial·y' + dy:
580    ///
581    /// ```text
582    /// ∂y''/∂x' = y'·∂radial/∂r²·∂r²/∂x' + ∂dy/∂x'
583    ///          = y'·dradial_dr2·2x' + 2p₁x' + 2p₂y'
584    ///          = 2x'y'·dradial_dr2 + 2p₁x' + 2p₂y'
585    ///
586    /// ∂y''/∂y' = radial + y'·∂radial/∂r²·∂r²/∂y' + ∂dy/∂y'
587    ///          = radial + y'·dradial_dr2·2y' + 6p₁y' + 2p₂x'
588    ///          = radial + 2y'²·dradial_dr2 + 6p₁y' + 2p₂x'
589    /// ```
590    ///
591    /// Final projection derivatives (u = fx·x'' + cx, v = fy·y'' + cy):
592    /// ```text
593    /// ∂u/∂x'' = fx,  ∂u/∂y'' = 0
594    /// ∂v/∂x'' = 0,   ∂v/∂y'' = fy
595    /// ```
596    ///
597    /// Chain rule:
598    ///
599    /// ```text
600    /// ∂u/∂x = fx·(∂x''/∂x'·∂x'/∂x + ∂x''/∂y'·∂y'/∂x)
601    ///       = fx·(∂x''/∂x'·1/z + 0)
602    ///       = fx·∂x''/∂x'·1/z
603    ///
604    /// ∂u/∂y = fx·(∂x''/∂x'·∂x'/∂y + ∂x''/∂y'·∂y'/∂y)
605    ///       = fx·(0 + ∂x''/∂y'·1/z)
606    ///       = fx·∂x''/∂y'·1/z
607    ///
608    /// ∂u/∂z = fx·(∂x''/∂x'·∂x'/∂z + ∂x''/∂y'·∂y'/∂z)
609    ///       = fx·(∂x''/∂x'·(-x'/z) + ∂x''/∂y'·(-y'/z))
610    /// ```
611    ///
612    /// Similar derivations apply for ∂v/∂x, ∂v/∂y, ∂v/∂z.
613    ///
614    /// ## Matrix Form
615    ///
616    /// ```text
617    /// J = [ ∂u/∂x  ∂u/∂y  ∂u/∂z ]
618    ///     [ ∂v/∂x  ∂v/∂y  ∂v/∂z ]
619    /// ```
620    ///
621    /// ## References
622    ///
623    /// - Brown, "Decentering Distortion of Lenses", Photogrammetric Engineering 1966
624    /// - OpenCV Camera Calibration Documentation
625    /// - Hartley & Zisserman, "Multiple View Geometry", Chapter 7
626    ///
627    /// ## Numerical Verification
628    ///
629    /// Verified against numerical differentiation in `test_jacobian_point_numerical()`.
630    fn jacobian_point(&self, p_cam: &Vector3<f64>) -> Self::PointJacobian {
631        let inv_z = 1.0 / p_cam.z;
632        let x_prime = p_cam.x * inv_z;
633        let y_prime = p_cam.y * inv_z;
634
635        let r2 = x_prime * x_prime + y_prime * y_prime;
636        let r4 = r2 * r2;
637        let r6 = r4 * r2;
638
639        let (k1, k2, p1, p2, k3) = self.distortion_params();
640
641        let radial = 1.0 + k1 * r2 + k2 * r4 + k3 * r6;
642        let dradial_dr2 = k1 + 2.0 * k2 * r2 + 3.0 * k3 * r4;
643
644        // Derivatives of distorted coordinates w.r.t. normalized coordinates
645        // x_dist = radial·x' + dx where dx = 2p₁x'y' + p₂(r² + 2x'²)
646        // ∂x_dist/∂x' = radial + x'·∂radial/∂r²·∂r²/∂x' + ∂dx/∂x'
647        //             = radial + x'·dradial_dr2·2x' + (2p₁y' + p₂·(2x' + 4x'))
648        //             = radial + 2x'²·dradial_dr2 + 2p₁y' + 6p₂x'
649        let dx_dist_dx_prime = radial
650            + 2.0 * x_prime * x_prime * dradial_dr2
651            + 2.0 * p1 * y_prime
652            + 6.0 * p2 * x_prime;
653
654        // ∂x_dist/∂y' = x'·∂radial/∂r²·∂r²/∂y' + ∂dx/∂y'
655        //             = x'·dradial_dr2·2y' + (2p₁x' + 2p₂y')
656        let dx_dist_dy_prime =
657            2.0 * x_prime * y_prime * dradial_dr2 + 2.0 * p1 * x_prime + 2.0 * p2 * y_prime;
658
659        // y_dist = radial·y' + dy where dy = p₁(r² + 2y'²) + 2p₂x'y'
660        // ∂y_dist/∂x' = y'·∂radial/∂r²·∂r²/∂x' + ∂dy/∂x'
661        //             = y'·dradial_dr2·2x' + (p₁·2x' + 2p₂y')
662        let dy_dist_dx_prime =
663            2.0 * y_prime * x_prime * dradial_dr2 + 2.0 * p1 * x_prime + 2.0 * p2 * y_prime;
664
665        // ∂y_dist/∂y' = radial + y'·∂radial/∂r²·∂r²/∂y' + ∂dy/∂y'
666        //             = radial + y'·dradial_dr2·2y' + (p₁·(2y' + 4y') + 2p₂x')
667        //             = radial + 2y'²·dradial_dr2 + 6p₁y' + 2p₂x'
668        let dy_dist_dy_prime = radial
669            + 2.0 * y_prime * y_prime * dradial_dr2
670            + 6.0 * p1 * y_prime
671            + 2.0 * p2 * x_prime;
672
673        // Derivatives of normalized coordinates w.r.t. camera coordinates
674        // x' = x/z => ∂x'/∂x = 1/z, ∂x'/∂y = 0, ∂x'/∂z = -x/z²
675        // y' = y/z => ∂y'/∂x = 0, ∂y'/∂y = 1/z, ∂y'/∂z = -y/z²
676
677        // Chain rule: ∂(u,v)/∂(x,y,z) = ∂(u,v)/∂(x_dist,y_dist) · ∂(x_dist,y_dist)/∂(x',y') · ∂(x',y')/∂(x,y,z)
678
679        let du_dx = self.pinhole.fx * (dx_dist_dx_prime * inv_z);
680        let du_dy = self.pinhole.fx * (dx_dist_dy_prime * inv_z);
681        let du_dz = self.pinhole.fx
682            * (dx_dist_dx_prime * (-x_prime * inv_z) + dx_dist_dy_prime * (-y_prime * inv_z));
683
684        let dv_dx = self.pinhole.fy * (dy_dist_dx_prime * inv_z);
685        let dv_dy = self.pinhole.fy * (dy_dist_dy_prime * inv_z);
686        let dv_dz = self.pinhole.fy
687            * (dy_dist_dx_prime * (-x_prime * inv_z) + dy_dist_dy_prime * (-y_prime * inv_z));
688
689        SMatrix::<f64, 2, 3>::new(du_dx, du_dy, du_dz, dv_dx, dv_dy, dv_dz)
690    }
691
692    /// Computes the Jacobian of the projection with respect to intrinsic parameters (2×9).
693    ///
694    /// # Mathematical Derivation
695    ///
696    /// The Radial-Tangential camera has 9 intrinsic parameters: [fx, fy, cx, cy, k₁, k₂, p₁, p₂, k₃]
697    ///
698    /// ## Projection Equations
699    ///
700    /// ```text
701    /// x' = x/z,  y' = y/z
702    /// r² = x'² + y'²
703    /// radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
704    /// dx = 2·p₁·x'·y' + p₂·(r² + 2·x'²)
705    /// dy = p₁·(r² + 2·y'²) + 2·p₂·x'·y'
706    /// x'' = radial·x' + dx
707    /// y'' = radial·y' + dy
708    /// u = fx·x'' + cx
709    /// v = fy·y'' + cy
710    /// ```
711    ///
712    /// ## Jacobian Structure
713    ///
714    /// ```text
715    /// J = [ ∂u/∂fx  ∂u/∂fy  ∂u/∂cx  ∂u/∂cy  ∂u/∂k₁  ∂u/∂k₂  ∂u/∂p₁  ∂u/∂p₂  ∂u/∂k₃ ]
716    ///     [ ∂v/∂fx  ∂v/∂fy  ∂v/∂cx  ∂v/∂cy  ∂v/∂k₁  ∂v/∂k₂  ∂v/∂p₁  ∂v/∂p₂  ∂v/∂k₃ ]
717    /// ```
718    ///
719    /// Linear parameters (fx, fy, cx, cy):
720    /// ```text
721    /// ∂u/∂fx = x'',  ∂u/∂fy = 0,   ∂u/∂cx = 1,  ∂u/∂cy = 0
722    /// ∂v/∂fx = 0,    ∂v/∂fy = y'', ∂v/∂cx = 0,  ∂v/∂cy = 1
723    /// ```
724    ///
725    /// Radial distortion coefficients (k₁, k₂, k₃):
726    ///
727    /// Each k_i affects the radial distortion component:
728    ///
729    /// ```text
730    /// ∂radial/∂k₁ = r²
731    /// ∂radial/∂k₂ = r⁴
732    /// ∂radial/∂k₃ = r⁶
733    /// ```
734    ///
735    /// By chain rule (x'' = radial·x' + dx, y'' = radial·y' + dy):
736    ///
737    /// ```text
738    /// ∂x''/∂k₁ = x'·r²
739    /// ∂x''/∂k₂ = x'·r⁴
740    /// ∂x''/∂k₃ = x'·r⁶
741    ///
742    /// ∂y''/∂k₁ = y'·r²
743    /// ∂y''/∂k₂ = y'·r⁴
744    /// ∂y''/∂k₃ = y'·r⁶
745    /// ```
746    ///
747    /// Then:
748    ///
749    /// ```text
750    /// ∂u/∂k₁ = fx·x'·r²
751    /// ∂u/∂k₂ = fx·x'·r⁴
752    /// ∂u/∂k₃ = fx·x'·r⁶
753    ///
754    /// ∂v/∂k₁ = fy·y'·r²
755    /// ∂v/∂k₂ = fy·y'·r⁴
756    /// ∂v/∂k₃ = fy·y'·r⁶
757    /// ```
758    ///
759    /// Tangential distortion coefficients (p₁, p₂):
760    /// ```text
761    /// ∂dx/∂p₁ = 2x'y',  ∂dy/∂p₁ = r² + 2y'²
762    /// ∂u/∂p₁ = fx·2x'y',  ∂v/∂p₁ = fy·(r² + 2y'²)
763    /// ∂dx/∂p₂ = r² + 2x'²,  ∂dy/∂p₂ = 2x'y'
764    /// ∂u/∂p₂ = fx·(r² + 2x'²),  ∂v/∂p₂ = fy·2x'y'
765    /// ```
766    ///
767    /// Matrix form:
768    ///
769    /// ```text
770    /// J = [ x''  0   1  0  fx·x'·r²  fx·x'·r⁴  fx·2x'y'    fx·(r²+2x'²)  fx·x'·r⁶ ]
771    ///     [  0  y''  0  1  fy·y'·r²  fy·y'·r⁴  fy·(r²+2y'²) fy·2x'y'      fy·y'·r⁶ ]
772    /// ```
773    ///
774    /// ## References
775    ///
776    /// - Brown, "Decentering Distortion of Lenses", 1966
777    /// - OpenCV Camera Calibration Documentation
778    /// - Hartley & Zisserman, "Multiple View Geometry", Chapter 7
779    ///
780    /// ## Numerical Verification
781    ///
782    /// Verified in `test_jacobian_intrinsics_numerical()` with tolerance < 1e-5.
783    fn jacobian_intrinsics(&self, p_cam: &Vector3<f64>) -> Self::IntrinsicJacobian {
784        let inv_z = 1.0 / p_cam.z;
785        let x_prime = p_cam.x * inv_z;
786        let y_prime = p_cam.y * inv_z;
787
788        let r2 = x_prime * x_prime + y_prime * y_prime;
789        let r4 = r2 * r2;
790        let r6 = r4 * r2;
791
792        let (k1, k2, p1, p2, k3) = self.distortion_params();
793
794        let radial = 1.0 + k1 * r2 + k2 * r4 + k3 * r6;
795
796        let xy = x_prime * y_prime;
797        let dx = 2.0 * p1 * xy + p2 * (r2 + 2.0 * x_prime * x_prime);
798        let dy = p1 * (r2 + 2.0 * y_prime * y_prime) + 2.0 * p2 * xy;
799
800        let x_distorted = radial * x_prime + dx;
801        let y_distorted = radial * y_prime + dy;
802
803        // ∂u/∂fx = x_distorted, ∂u/∂fy = 0, ∂u/∂cx = 1, ∂u/∂cy = 0
804        // ∂v/∂fx = 0, ∂v/∂fy = y_distorted, ∂v/∂cx = 0, ∂v/∂cy = 1
805
806        // Distortion parameter derivatives
807        let du_dk1 = self.pinhole.fx * x_prime * r2;
808        let du_dk2 = self.pinhole.fx * x_prime * r4;
809        let du_dp1 = self.pinhole.fx * 2.0 * xy;
810        let du_dp2 = self.pinhole.fx * (r2 + 2.0 * x_prime * x_prime);
811        let du_dk3 = self.pinhole.fx * x_prime * r6;
812
813        let dv_dk1 = self.pinhole.fy * y_prime * r2;
814        let dv_dk2 = self.pinhole.fy * y_prime * r4;
815        let dv_dp1 = self.pinhole.fy * (r2 + 2.0 * y_prime * y_prime);
816        let dv_dp2 = self.pinhole.fy * 2.0 * xy;
817        let dv_dk3 = self.pinhole.fy * y_prime * r6;
818
819        SMatrix::<f64, 2, 9>::from_row_slice(&[
820            x_distorted,
821            0.0,
822            1.0,
823            0.0,
824            du_dk1,
825            du_dk2,
826            du_dp1,
827            du_dp2,
828            du_dk3,
829            0.0,
830            y_distorted,
831            0.0,
832            1.0,
833            dv_dk1,
834            dv_dk2,
835            dv_dp1,
836            dv_dp2,
837            dv_dk3,
838        ])
839    }
840
841    /// Validates the camera parameters.
842    ///
843    /// # Validation Rules
844    ///
845    /// - fx, fy must be positive (> 0)
846    /// - fx, fy must be finite
847    /// - cx, cy must be finite
848    /// - k₁, k₂, p₁, p₂, k₃ must be finite
849    ///
850    /// # Errors
851    ///
852    /// Returns [`CameraModelError`] if any parameter violates validation rules.
853    fn validate_params(&self) -> Result<(), CameraModelError> {
854        self.pinhole.validate()?;
855        self.get_distortion().validate()
856    }
857
858    /// Returns the pinhole parameters.
859    ///
860    /// # Returns
861    ///
862    /// A [`PinholeParams`] struct containing the focal lengths (fx, fy) and principal point (cx, cy).
863    fn get_pinhole_params(&self) -> PinholeParams {
864        self.pinhole
865    }
866
867    /// Returns the distortion model parameters.
868    ///
869    /// # Returns
870    ///
871    /// The [`DistortionModel`] associated with this camera (typically [`DistortionModel::BrownConrady`]).
872    fn get_distortion(&self) -> DistortionModel {
873        self.distortion
874    }
875
876    /// Returns the name of the camera model.
877    ///
878    /// # Returns
879    ///
880    /// The string `"rad_tan"`.
881    fn get_model_name(&self) -> &'static str {
882        "rad_tan"
883    }
884}
885
886#[cfg(test)]
887mod tests {
888    use super::*;
889    use nalgebra::{Matrix2xX, Matrix3xX};
890
891    type TestResult = Result<(), Box<dyn std::error::Error>>;
892
893    #[test]
894    fn test_radtan_camera_creation() -> TestResult {
895        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
896        let distortion = DistortionModel::BrownConrady {
897            k1: 0.1,
898            k2: 0.01,
899            p1: 0.001,
900            p2: 0.002,
901            k3: 0.001,
902        };
903        let camera = RadTanCamera::new(pinhole, distortion)?;
904        assert_eq!(camera.pinhole.fx, 300.0);
905        let (k1, _, p1, _, _) = camera.distortion_params();
906        assert_eq!(k1, 0.1);
907        assert_eq!(p1, 0.001);
908        Ok(())
909    }
910
911    #[test]
912    fn test_projection_at_optical_axis() -> TestResult {
913        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
914        let distortion = DistortionModel::BrownConrady {
915            k1: 0.0,
916            k2: 0.0,
917            p1: 0.0,
918            p2: 0.0,
919            k3: 0.0,
920        };
921        let camera = RadTanCamera::new(pinhole, distortion)?;
922        let p_cam = Vector3::new(0.0, 0.0, 1.0);
923        let uv = camera.project(&p_cam)?;
924
925        assert!((uv.x - 320.0).abs() < crate::PROJECTION_TEST_TOLERANCE);
926        assert!((uv.y - 240.0).abs() < crate::PROJECTION_TEST_TOLERANCE);
927
928        Ok(())
929    }
930
931    #[test]
932    fn test_jacobian_point_numerical() -> TestResult {
933        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
934        let distortion = DistortionModel::BrownConrady {
935            k1: 0.1,
936            k2: 0.01,
937            p1: 0.001,
938            p2: 0.002,
939            k3: 0.001,
940        };
941        let camera = RadTanCamera::new(pinhole, distortion)?;
942        let p_cam = Vector3::new(0.1, 0.2, 1.0);
943
944        let jac_analytical = camera.jacobian_point(&p_cam);
945        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
946
947        for i in 0..3 {
948            let mut p_plus = p_cam;
949            let mut p_minus = p_cam;
950            p_plus[i] += eps;
951            p_minus[i] -= eps;
952
953            let uv_plus = camera.project(&p_plus)?;
954            let uv_minus = camera.project(&p_minus)?;
955            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
956
957            for r in 0..2 {
958                assert!(
959                    jac_analytical[(r, i)].is_finite(),
960                    "Jacobian [{r},{i}] is not finite"
961                );
962                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
963                assert!(
964                    diff < crate::JACOBIAN_TEST_TOLERANCE,
965                    "Mismatch at ({}, {})",
966                    r,
967                    i
968                );
969            }
970        }
971        Ok(())
972    }
973
974    #[test]
975    fn test_jacobian_intrinsics_numerical() -> TestResult {
976        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
977        let distortion = DistortionModel::BrownConrady {
978            k1: 0.1,
979            k2: 0.01,
980            p1: 0.001,
981            p2: 0.002,
982            k3: 0.001,
983        };
984        let camera = RadTanCamera::new(pinhole, distortion)?;
985        let p_cam = Vector3::new(0.1, 0.2, 1.0);
986
987        let jac_analytical = camera.jacobian_intrinsics(&p_cam);
988        let params: DVector<f64> = (&camera).into();
989        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
990
991        for i in 0..9 {
992            let mut params_plus = params.clone();
993            let mut params_minus = params.clone();
994            params_plus[i] += eps;
995            params_minus[i] -= eps;
996
997            let cam_plus = RadTanCamera::try_from(params_plus.as_slice())?;
998            let cam_minus = RadTanCamera::try_from(params_minus.as_slice())?;
999
1000            let uv_plus = cam_plus.project(&p_cam)?;
1001            let uv_minus = cam_minus.project(&p_cam)?;
1002            let num_jac = (uv_plus - uv_minus) / (2.0 * eps);
1003
1004            for r in 0..2 {
1005                assert!(
1006                    jac_analytical[(r, i)].is_finite(),
1007                    "Jacobian [{r},{i}] is not finite"
1008                );
1009                let diff = (jac_analytical[(r, i)] - num_jac[r]).abs();
1010                assert!(
1011                    diff < crate::JACOBIAN_TEST_TOLERANCE,
1012                    "Mismatch at ({}, {})",
1013                    r,
1014                    i
1015                );
1016            }
1017        }
1018        Ok(())
1019    }
1020
1021    #[test]
1022    fn test_rad_tan_from_into_traits() -> TestResult {
1023        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1024        let distortion = DistortionModel::BrownConrady {
1025            k1: 0.1,
1026            k2: 0.01,
1027            p1: 0.001,
1028            p2: 0.002,
1029            k3: 0.001,
1030        };
1031        let camera = RadTanCamera::new(pinhole, distortion)?;
1032
1033        // Test conversion to DVector
1034        let params: DVector<f64> = (&camera).into();
1035        assert_eq!(params.len(), 9);
1036        assert_eq!(params[0], 300.0);
1037        assert_eq!(params[1], 300.0);
1038        assert_eq!(params[2], 320.0);
1039        assert_eq!(params[3], 240.0);
1040        assert_eq!(params[4], 0.1);
1041        assert_eq!(params[5], 0.01);
1042        assert_eq!(params[6], 0.001);
1043        assert_eq!(params[7], 0.002);
1044        assert_eq!(params[8], 0.001);
1045
1046        // Test conversion to array
1047        let arr: [f64; 9] = (&camera).into();
1048        assert_eq!(
1049            arr,
1050            [300.0, 300.0, 320.0, 240.0, 0.1, 0.01, 0.001, 0.002, 0.001]
1051        );
1052
1053        // Test conversion from slice
1054        let params_slice = [350.0, 350.0, 330.0, 250.0, 0.2, 0.02, 0.002, 0.003, 0.002];
1055        let camera2 = RadTanCamera::try_from(&params_slice[..])?;
1056        assert_eq!(camera2.pinhole.fx, 350.0);
1057        assert_eq!(camera2.pinhole.fy, 350.0);
1058        assert_eq!(camera2.pinhole.cx, 330.0);
1059        assert_eq!(camera2.pinhole.cy, 250.0);
1060        let (k1, k2, p1, p2, k3) = camera2.distortion_params();
1061        assert_eq!(k1, 0.2);
1062        assert_eq!(k2, 0.02);
1063        assert_eq!(p1, 0.002);
1064        assert_eq!(p2, 0.003);
1065        assert_eq!(k3, 0.002);
1066
1067        // Test conversion from array
1068        let camera3 =
1069            RadTanCamera::from([400.0, 400.0, 340.0, 260.0, 0.3, 0.03, 0.003, 0.004, 0.003]);
1070        assert_eq!(camera3.pinhole.fx, 400.0);
1071        assert_eq!(camera3.pinhole.fy, 400.0);
1072        let (k1, k2, p1, p2, k3) = camera3.distortion_params();
1073        assert_eq!(k1, 0.3);
1074        assert_eq!(k2, 0.03);
1075        assert_eq!(p1, 0.003);
1076        assert_eq!(p2, 0.004);
1077        assert_eq!(k3, 0.003);
1078
1079        Ok(())
1080    }
1081
1082    #[test]
1083    fn test_linear_estimation() -> TestResult {
1084        // Ground truth camera with radial distortion only (p1=p2=0)
1085        let gt_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1086        let gt_distortion = DistortionModel::BrownConrady {
1087            k1: 0.05,
1088            k2: 0.01,
1089            p1: 0.0,
1090            p2: 0.0,
1091            k3: 0.001,
1092        };
1093        let gt_camera = RadTanCamera::new(gt_pinhole, gt_distortion)?;
1094
1095        // Generate synthetic 3D points in camera frame
1096        let n_points = 50;
1097        let mut pts_3d = Matrix3xX::zeros(n_points);
1098        let mut pts_2d = Matrix2xX::zeros(n_points);
1099        let mut valid = 0;
1100
1101        for i in 0..n_points {
1102            let angle = i as f64 * 2.0 * std::f64::consts::PI / n_points as f64;
1103            let r = 0.1 + 0.3 * (i as f64 / n_points as f64);
1104            let p3d = Vector3::new(r * angle.cos(), r * angle.sin(), 1.0);
1105
1106            if let Ok(p2d) = gt_camera.project(&p3d) {
1107                pts_3d.set_column(valid, &p3d);
1108                pts_2d.set_column(valid, &p2d);
1109                valid += 1;
1110            }
1111        }
1112        let pts_3d = pts_3d.columns(0, valid).into_owned();
1113        let pts_2d = pts_2d.columns(0, valid).into_owned();
1114
1115        // Initial camera with zero distortion
1116        let init_pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1117        let init_distortion = DistortionModel::BrownConrady {
1118            k1: 0.0,
1119            k2: 0.0,
1120            p1: 0.0,
1121            p2: 0.0,
1122            k3: 0.0,
1123        };
1124        let mut camera = RadTanCamera::new(init_pinhole, init_distortion)?;
1125
1126        camera.linear_estimation(&pts_3d, &pts_2d)?;
1127
1128        // Verify reprojection error
1129        for i in 0..valid {
1130            let col = pts_3d.column(i);
1131            let projected = camera.project(&Vector3::new(col[0], col[1], col[2]))?;
1132            let err = ((projected.x - pts_2d[(0, i)]).powi(2)
1133                + (projected.y - pts_2d[(1, i)]).powi(2))
1134            .sqrt();
1135            assert!(err < 1.0, "Reprojection error too large: {err}");
1136        }
1137
1138        Ok(())
1139    }
1140
1141    #[test]
1142    fn test_project_unproject_round_trip() -> TestResult {
1143        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1144        let distortion = DistortionModel::BrownConrady {
1145            k1: 0.1,
1146            k2: 0.01,
1147            p1: 0.001,
1148            p2: 0.002,
1149            k3: 0.001,
1150        };
1151        let camera = RadTanCamera::new(pinhole, distortion)?;
1152
1153        let test_points = [
1154            Vector3::new(0.1, 0.2, 1.0),
1155            Vector3::new(-0.3, 0.1, 2.0),
1156            Vector3::new(0.05, -0.1, 0.5),
1157        ];
1158
1159        for p_cam in &test_points {
1160            let uv = camera.project(p_cam)?;
1161            let ray = camera.unproject(&uv)?;
1162            let dot = ray.dot(&p_cam.normalize());
1163            assert!(
1164                (dot - 1.0).abs() < 1e-5,
1165                "Round-trip failed: dot={dot}, expected ~1.0"
1166            );
1167        }
1168
1169        Ok(())
1170    }
1171
1172    #[test]
1173    fn test_project_returns_error_behind_camera() -> TestResult {
1174        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1175        let distortion = DistortionModel::BrownConrady {
1176            k1: 0.0,
1177            k2: 0.0,
1178            p1: 0.0,
1179            p2: 0.0,
1180            k3: 0.0,
1181        };
1182        let camera = RadTanCamera::new(pinhole, distortion)?;
1183        assert!(camera.project(&Vector3::new(0.0, 0.0, -1.0)).is_err());
1184        Ok(())
1185    }
1186
1187    #[test]
1188    fn test_project_at_min_depth_boundary() -> TestResult {
1189        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1190        let distortion = DistortionModel::BrownConrady {
1191            k1: 0.0,
1192            k2: 0.0,
1193            p1: 0.0,
1194            p2: 0.0,
1195            k3: 0.0,
1196        };
1197        let camera = RadTanCamera::new(pinhole, distortion)?;
1198        let p_min = Vector3::new(0.0, 0.0, crate::MIN_DEPTH);
1199        if let Ok(uv) = camera.project(&p_min) {
1200            assert!(uv.x.is_finite() && uv.y.is_finite());
1201        }
1202        Ok(())
1203    }
1204
1205    #[test]
1206    fn test_projection_off_axis() -> TestResult {
1207        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1208        let distortion = DistortionModel::BrownConrady {
1209            k1: 0.1,
1210            k2: 0.01,
1211            p1: 0.001,
1212            p2: 0.002,
1213            k3: 0.001,
1214        };
1215        let camera = RadTanCamera::new(pinhole, distortion)?;
1216        let p_cam = Vector3::new(0.3, 0.0, 1.0);
1217        let uv = camera.project(&p_cam)?;
1218        assert!(
1219            uv.x > 320.0,
1220            "off-axis point should project right of principal point"
1221        );
1222        assert!(
1223            (uv.y - 240.0).abs() < 5.0,
1224            "y should be close to cy for horizontal offset"
1225        );
1226        Ok(())
1227    }
1228
1229    #[test]
1230    fn test_unproject_center_pixel() -> TestResult {
1231        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1232        let distortion = DistortionModel::BrownConrady {
1233            k1: 0.1,
1234            k2: 0.01,
1235            p1: 0.0,
1236            p2: 0.0,
1237            k3: 0.001,
1238        };
1239        let camera = RadTanCamera::new(pinhole, distortion)?;
1240        let uv = Vector2::new(320.0, 240.0);
1241        let ray = camera.unproject(&uv)?;
1242        assert!(ray.x.abs() < 1e-5, "x should be ~0, got {}", ray.x);
1243        assert!(ray.y.abs() < 1e-5, "y should be ~0, got {}", ray.y);
1244        assert!((ray.z - 1.0).abs() < 1e-5, "z should be ~1, got {}", ray.z);
1245        Ok(())
1246    }
1247
1248    #[test]
1249    fn test_batch_projection_matches_individual() -> TestResult {
1250        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1251        let distortion = DistortionModel::BrownConrady {
1252            k1: 0.1,
1253            k2: 0.01,
1254            p1: 0.001,
1255            p2: 0.002,
1256            k3: 0.001,
1257        };
1258        let camera = RadTanCamera::new(pinhole, distortion)?;
1259        let pts = Matrix3xX::from_columns(&[
1260            Vector3::new(0.0, 0.0, 1.0),
1261            Vector3::new(0.3, 0.2, 1.5),
1262            Vector3::new(-0.4, 0.1, 2.0),
1263        ]);
1264        let batch = camera.project_batch(&pts);
1265        for i in 0..3 {
1266            let col = pts.column(i);
1267            let p = camera.project(&Vector3::new(col[0], col[1], col[2]))?;
1268            assert!(
1269                (batch[(0, i)] - p.x).abs() < 1e-10,
1270                "batch u mismatch at col {i}"
1271            );
1272            assert!(
1273                (batch[(1, i)] - p.y).abs() < 1e-10,
1274                "batch v mismatch at col {i}"
1275            );
1276        }
1277        Ok(())
1278    }
1279
1280    #[test]
1281    fn test_jacobian_dimensions() -> TestResult {
1282        let pinhole = PinholeParams::new(300.0, 300.0, 320.0, 240.0)?;
1283        let distortion = DistortionModel::BrownConrady {
1284            k1: 0.1,
1285            k2: 0.01,
1286            p1: 0.001,
1287            p2: 0.002,
1288            k3: 0.001,
1289        };
1290        let camera = RadTanCamera::new(pinhole, distortion)?;
1291        let p_cam = Vector3::new(0.1, 0.2, 1.0);
1292        let jac_point = camera.jacobian_point(&p_cam);
1293        assert_eq!(jac_point.nrows(), 2);
1294        assert_eq!(jac_point.ncols(), 3);
1295        let jac_intr = camera.jacobian_intrinsics(&p_cam);
1296        assert_eq!(jac_intr.nrows(), 2);
1297        assert_eq!(jac_intr.ncols(), 9); // RadTanCamera::INTRINSIC_DIM = 9
1298        Ok(())
1299    }
1300}