Skip to main content

apex_camera_models/
bal_pinhole.rs

1//! BAL (Bundle Adjustment in the Large) pinhole camera model.
2//!
3//! This module implements a pinhole camera model that follows the BAL dataset convention
4//! where cameras look down the -Z axis (negative Z in front of camera).
5
6use crate::{CameraModel, CameraModelError, DistortionModel, PinholeParams, skew_symmetric};
7use apex_manifolds::LieGroup;
8use apex_manifolds::se3::SE3;
9use nalgebra::{DVector, SMatrix, Vector2, Vector3};
10
11/// Strict BAL camera model matching Snavely's Bundler convention.
12///
13/// This camera model uses EXACTLY 3 intrinsic parameters matching the BAL file format:
14/// - Single focal length (f): fx = fy
15/// - Two radial distortion coefficients (k1, k2)
16/// - NO principal point (cx = cy = 0 by convention)
17///
18/// This matches the intrinsic parameterization used by:
19/// - Ceres Solver bundle adjustment examples
20/// - GTSAM bundle adjustment
21/// - Original Bundler software
22///
23/// # Parameters
24///
25/// - `f`: Single focal length in pixels (fx = fy = f)
26/// - `k1`: First radial distortion coefficient
27/// - `k2`: Second radial distortion coefficient
28///
29/// # Projection Model
30///
31/// For a 3D point `p_cam = (x, y, z)` in camera frame where z < 0:
32/// ```text
33/// x_n = x / (-z)
34/// y_n = y / (-z)
35/// r² = x_n² + y_n²
36/// distortion = 1 + k1*r² + k2*r⁴
37/// x_d = x_n * distortion
38/// y_d = y_n * distortion
39/// u = f * x_d      (no cx offset)
40/// v = f * y_d      (no cy offset)
41/// ```
42///
43/// # Usage
44///
45/// This camera model should be used for bundle adjustment problems that read
46/// BAL format files, to ensure parameter compatibility and avoid degenerate
47/// optimization (extra DOF from fx≠fy or non-zero principal point).
48#[derive(Debug, Clone, Copy, PartialEq)]
49pub struct BALPinholeCameraStrict {
50    /// Single focal length (fx = fy = f)
51    pub f: f64,
52    pub distortion: DistortionModel,
53}
54
55impl BALPinholeCameraStrict {
56    /// Creates a new strict BAL pinhole camera with distortion.
57    ///
58    /// # Arguments
59    ///
60    /// * `pinhole` - Pinhole parameters. MUST have `fx == fy` and `cx == cy == 0` for strict BAL format.
61    /// * `distortion` - MUST be [`DistortionModel::Radial`] with `k1` and `k2`.
62    ///
63    /// # Returns
64    ///
65    /// Returns a new `BALPinholeCameraStrict` instance if parameters satisfy the strict BAL constraints.
66    ///
67    /// # Errors
68    ///
69    /// Returns [`CameraModelError::InvalidParams`] if:
70    /// - `pinhole.fx != pinhole.fy` (strict BAL requires single focal length).
71    /// - `pinhole.cx != 0.0` or `pinhole.cy != 0.0` (strict BAL has no principal point offset).
72    /// - `distortion` is not [`DistortionModel::Radial`].
73    ///
74    /// # Example
75    ///
76    /// ```
77    /// use apex_camera_models::{BALPinholeCameraStrict, PinholeParams, DistortionModel};
78    ///
79    /// let pinhole = PinholeParams::new(500.0, 500.0, 0.0, 0.0)?;
80    /// let distortion = DistortionModel::Radial { k1: -0.1, k2: 0.01 };
81    /// let camera = BALPinholeCameraStrict::new(pinhole, distortion)?;
82    /// # Ok::<(), apex_camera_models::CameraModelError>(())
83    /// ```
84    pub fn new(
85        pinhole: PinholeParams,
86        distortion: DistortionModel,
87    ) -> Result<Self, CameraModelError> {
88        // Validate strict BAL constraints on input
89        if (pinhole.fx - pinhole.fy).abs() > 1e-10 {
90            return Err(CameraModelError::InvalidParams(
91                "BALPinholeCameraStrict requires fx = fy (single focal length)".to_string(),
92            ));
93        }
94        if pinhole.cx.abs() > 1e-10 || pinhole.cy.abs() > 1e-10 {
95            return Err(CameraModelError::InvalidParams(
96                "BALPinholeCameraStrict requires cx = cy = 0 (no principal point offset)"
97                    .to_string(),
98            ));
99        }
100
101        let camera = Self {
102            f: pinhole.fx, // Use fx as the single focal length
103            distortion,
104        };
105        camera.validate_params()?;
106        Ok(camera)
107    }
108
109    /// Creates a strict BAL pinhole camera without distortion (k1=0, k2=0).
110    ///
111    /// This is a convenience constructor for the common case of no distortion.
112    ///
113    /// # Arguments
114    ///
115    /// * `f` - The single focal length in pixels.
116    ///
117    /// # Returns
118    ///
119    /// Returns a new `BALPinholeCameraStrict` instance with zero distortion.
120    ///
121    /// # Errors
122    ///
123    /// Returns [`CameraModelError`] if the focal length is invalid (e.g., negative).
124    pub fn new_no_distortion(f: f64) -> Result<Self, CameraModelError> {
125        let pinhole = PinholeParams::new(f, f, 0.0, 0.0)?;
126        let distortion = DistortionModel::Radial { k1: 0.0, k2: 0.0 };
127        Self::new(pinhole, distortion)
128    }
129
130    /// Helper method to extract distortion parameters.
131    ///
132    /// # Returns
133    ///
134    /// Returns a tuple `(k1, k2)` containing the radial distortion coefficients.
135    /// If the distortion model is not radial (which shouldn't happen for valid instances), returns `(0.0, 0.0)`.
136    fn distortion_params(&self) -> (f64, f64) {
137        match self.distortion {
138            DistortionModel::Radial { k1, k2 } => (k1, k2),
139            _ => (0.0, 0.0),
140        }
141    }
142
143    /// Checks if a 3D point satisfies the projection condition.
144    ///
145    /// For BAL, the condition is `z < -epsilon` (negative Z is in front of camera).
146    ///
147    /// # Arguments
148    ///
149    /// * `z` - The z-coordinate of the point in the camera frame.
150    ///
151    /// # Returns
152    ///
153    /// Returns `true` if the point is safely in front of the camera, `false` otherwise.
154    fn check_projection_condition(&self, z: f64) -> bool {
155        z < -crate::MIN_DEPTH
156    }
157}
158
159/// Convert camera to dynamic vector of intrinsic parameters.
160///
161/// # Layout
162///
163/// The parameters are ordered as: [f, k1, k2]
164impl From<&BALPinholeCameraStrict> for DVector<f64> {
165    fn from(camera: &BALPinholeCameraStrict) -> Self {
166        let (k1, k2) = camera.distortion_params();
167        DVector::from_vec(vec![camera.f, k1, k2])
168    }
169}
170
171/// Convert camera to fixed-size array of intrinsic parameters.
172///
173/// # Layout
174///
175/// The parameters are ordered as: [f, k1, k2]
176impl From<&BALPinholeCameraStrict> for [f64; 3] {
177    fn from(camera: &BALPinholeCameraStrict) -> Self {
178        let (k1, k2) = camera.distortion_params();
179        [camera.f, k1, k2]
180    }
181}
182
183/// Create camera from slice of intrinsic parameters.
184///
185/// # Layout
186///
187/// Expected parameter order: [f, k1, k2]
188///
189/// Returns an error if the slice has fewer than 3 elements.
190impl TryFrom<&[f64]> for BALPinholeCameraStrict {
191    type Error = CameraModelError;
192
193    fn try_from(params: &[f64]) -> Result<Self, Self::Error> {
194        if params.len() < 3 {
195            return Err(CameraModelError::InvalidParams(format!(
196                "BALPinholeCameraStrict requires at least 3 parameters, got {}",
197                params.len()
198            )));
199        }
200        Ok(Self {
201            f: params[0],
202            distortion: DistortionModel::Radial {
203                k1: params[1],
204                k2: params[2],
205            },
206        })
207    }
208}
209
210/// Create camera from fixed-size array of intrinsic parameters.
211///
212/// # Layout
213///
214/// Expected parameter order: [f, k1, k2]
215impl From<[f64; 3]> for BALPinholeCameraStrict {
216    fn from(params: [f64; 3]) -> Self {
217        Self {
218            f: params[0],
219            distortion: DistortionModel::Radial {
220                k1: params[1],
221                k2: params[2],
222            },
223        }
224    }
225}
226
227/// Creates a `BALPinholeCameraStrict` from a parameter slice with validation.
228///
229/// Returns a `Result` instead of panicking on invalid input.
230///
231/// # Errors
232///
233/// Returns `CameraModelError::InvalidParams` if fewer than 3 parameters are provided.
234/// Returns validation errors if focal length is non-positive or parameters are non-finite.
235pub fn try_from_params(params: &[f64]) -> Result<BALPinholeCameraStrict, CameraModelError> {
236    let camera = BALPinholeCameraStrict::try_from(params)?;
237    camera.validate_params()?;
238    Ok(camera)
239}
240
241impl CameraModel for BALPinholeCameraStrict {
242    const INTRINSIC_DIM: usize = 3; // f, k1, k2
243    type IntrinsicJacobian = SMatrix<f64, 2, 3>;
244    type PointJacobian = SMatrix<f64, 2, 3>;
245
246    /// Projects a 3D point to 2D image coordinates.
247    ///
248    /// # Mathematical Formula
249    ///
250    /// BAL/Bundler convention (camera looks down negative Z axis):
251    ///
252    /// ```text
253    /// x_n = x / (−z)
254    /// y_n = y / (−z)
255    /// r² = x_n² + y_n²
256    /// r⁴ = (r²)²
257    /// d = 1 + k₁·r² + k₂·r⁴
258    /// u = f · x_n · d
259    /// v = f · y_n · d
260    /// ```
261    ///
262    /// # Arguments
263    ///
264    /// * `p_cam` - 3D point in camera coordinate frame (x, y, z).
265    ///
266    /// # Returns
267    ///
268    /// Returns the 2D image coordinates (u, v) if valid.
269    ///
270    /// # Errors
271    ///
272    /// Returns [`CameraModelError::ProjectionOutOfBounds`] if point is not in front of camera (z ≥ 0).
273    fn project(&self, p_cam: &Vector3<f64>) -> Result<Vector2<f64>, CameraModelError> {
274        // BAL convention: negative Z is in front
275        if !self.check_projection_condition(p_cam.z) {
276            return Err(CameraModelError::ProjectionOutOfBounds);
277        }
278        let inv_neg_z = -1.0 / p_cam.z;
279
280        // Normalized coordinates
281        let x_n = p_cam.x * inv_neg_z;
282        let y_n = p_cam.y * inv_neg_z;
283
284        let (k1, k2) = self.distortion_params();
285
286        // Radial distortion
287        let r2 = x_n * x_n + y_n * y_n;
288        let r4 = r2 * r2;
289        let distortion = 1.0 + k1 * r2 + k2 * r4;
290
291        // Apply distortion and focal length (no principal point offset)
292        let x_d = x_n * distortion;
293        let y_d = y_n * distortion;
294
295        Ok(Vector2::new(self.f * x_d, self.f * y_d))
296    }
297
298    /// Computes the Jacobian of the projection function with respect to the 3D point in camera frame.
299    ///
300    /// # Mathematical Derivation
301    ///
302    /// The projection function maps a 3D point p_cam = (x, y, z) to 2D pixel coordinates (u, v).
303    ///
304    /// Normalized coordinates (BAL uses negative Z convention):
305    /// ```text
306    /// x_n = x / (-z) = x * inv_neg_z
307    /// y_n = y / (-z) = y * inv_neg_z
308    /// ```
309    ///
310    /// Jacobian of normalized coordinates:
311    /// ```text
312    /// ∂x_n/∂x = inv_neg_z = -1/z
313    /// ∂x_n/∂y = 0
314    /// ∂x_n/∂z = x_n * inv_neg_z
315    /// ∂y_n/∂x = 0
316    /// ∂y_n/∂y = inv_neg_z = -1/z
317    /// ∂y_n/∂z = y_n * inv_neg_z
318    /// ```
319    ///
320    /// Radial distortion:
321    ///
322    /// The radial distance squared and distortion factor:
323    /// ```text
324    /// r² = x_n² + y_n²
325    /// r⁴ = (r²)²
326    /// d(r²) = 1 + k1·r² + k2·r⁴
327    /// ```
328    ///
329    /// Distorted coordinates:
330    /// ```text
331    /// x_d = x_n · d(r²)
332    /// y_d = y_n · d(r²)
333    /// ```
334    ///
335    /// ### Derivatives of r² and d(r²):
336    /// ```text
337    /// ∂(r²)/∂x_n = 2·x_n
338    /// ∂(r²)/∂y_n = 2·y_n
339    ///
340    /// ∂d/∂(r²) = k1 + 2·k2·r²
341    /// ```
342    ///
343    /// ### Jacobian of distorted coordinates w.r.t. normalized:
344    /// ```text
345    /// ∂x_d/∂x_n = ∂(x_n · d)/∂x_n = d + x_n · (∂d/∂(r²)) · (∂(r²)/∂x_n)
346    ///           = d + x_n · (k1 + 2·k2·r²) · 2·x_n
347    ///
348    /// ∂x_d/∂y_n = x_n · (∂d/∂(r²)) · (∂(r²)/∂y_n)
349    ///           = x_n · (k1 + 2·k2·r²) · 2·y_n
350    ///
351    /// ∂y_d/∂x_n = y_n · (k1 + 2·k2·r²) · 2·x_n
352    ///
353    /// ∂y_d/∂y_n = d + y_n · (k1 + 2·k2·r²) · 2·y_n
354    /// ```
355    ///
356    /// Pixel coordinates (strict BAL has no principal point):
357    /// ```text
358    /// u = f · x_d
359    /// v = f · y_d
360    /// ```
361    ///
362    /// Chain rule:
363    /// ```text
364    /// J = ∂(u,v)/∂(x_d,y_d) · ∂(x_d,y_d)/∂(x_n,y_n) · ∂(x_n,y_n)/∂(x,y,z)
365    /// ```
366    ///
367    /// Final results:
368    /// ```text
369    /// ∂u/∂x = f · (∂x_d/∂x_n · ∂x_n/∂x + ∂x_d/∂y_n · ∂y_n/∂x)
370    ///       = f · (∂x_d/∂x_n · inv_neg_z)
371    ///
372    /// ∂u/∂y = f · (∂x_d/∂y_n · inv_neg_z)
373    ///
374    /// ∂u/∂z = f · (∂x_d/∂x_n · ∂x_n/∂z + ∂x_d/∂y_n · ∂y_n/∂z)
375    ///
376    /// ∂v/∂x = f · (∂y_d/∂x_n · inv_neg_z)
377    ///
378    /// ∂v/∂y = f · (∂y_d/∂y_n · inv_neg_z)
379    ///
380    /// ∂v/∂z = f · (∂y_d/∂x_n · ∂x_n/∂z + ∂y_d/∂y_n · ∂y_n/∂z)
381    /// ```
382    ///
383    /// # Arguments
384    ///
385    /// * `p_cam` - 3D point in camera coordinate frame.
386    ///
387    /// # Returns
388    ///
389    /// Returns the 2x3 Jacobian matrix.
390    ///
391    /// # References
392    ///
393    /// - Snavely et al., "Photo Tourism: Exploring Photo Collections in 3D", SIGGRAPH 2006
394    /// - Agarwal et al., "Bundle Adjustment in the Large", ECCV 2010
395    /// - [Bundle Adjustment in the Large Dataset](https://grail.cs.washington.edu/projects/bal/)
396    ///
397    /// # Verification
398    ///
399    /// This Jacobian is verified against numerical differentiation in tests.
400    fn jacobian_point(&self, p_cam: &Vector3<f64>) -> Self::PointJacobian {
401        let inv_neg_z = -1.0 / p_cam.z;
402        let x_n = p_cam.x * inv_neg_z;
403        let y_n = p_cam.y * inv_neg_z;
404
405        let (k1, k2) = self.distortion_params();
406
407        // Radial distortion
408        let r2 = x_n * x_n + y_n * y_n;
409        let r4 = r2 * r2;
410        let distortion = 1.0 + k1 * r2 + k2 * r4;
411
412        // Derivative of distortion w.r.t. r²
413        let d_dist_dr2 = k1 + 2.0 * k2 * r2;
414
415        // Jacobian of normalized coordinates w.r.t. camera point
416        let dxn_dz = x_n * inv_neg_z;
417        let dyn_dz = y_n * inv_neg_z;
418
419        // Jacobian of distorted point w.r.t. normalized point
420        let dx_d_dxn = distortion + x_n * d_dist_dr2 * 2.0 * x_n;
421        let dx_d_dyn = x_n * d_dist_dr2 * 2.0 * y_n;
422        let dy_d_dxn = y_n * d_dist_dr2 * 2.0 * x_n;
423        let dy_d_dyn = distortion + y_n * d_dist_dr2 * 2.0 * y_n;
424
425        // Chain rule with single focal length f (not fx/fy)
426        let du_dx = self.f * (dx_d_dxn * inv_neg_z);
427        let du_dy = self.f * (dx_d_dyn * inv_neg_z);
428        let du_dz = self.f * (dx_d_dxn * dxn_dz + dx_d_dyn * dyn_dz);
429
430        let dv_dx = self.f * (dy_d_dxn * inv_neg_z);
431        let dv_dy = self.f * (dy_d_dyn * inv_neg_z);
432        let dv_dz = self.f * (dy_d_dxn * dxn_dz + dy_d_dyn * dyn_dz);
433
434        SMatrix::<f64, 2, 3>::new(du_dx, du_dy, du_dz, dv_dx, dv_dy, dv_dz)
435    }
436
437    /// Jacobian of projection w.r.t. camera pose (2×6).
438    ///
439    /// Computes ∂π/∂δξ where π is the projection and δξ ∈ se(3) is the pose perturbation.
440    ///
441    /// # Mathematical Derivation
442    ///
443    /// Given a 3D point in world frame `p_world` and camera pose `pose` (camera-to-world transformation),
444    /// we need the Jacobian ∂π/∂δξ.
445    ///
446    /// ## Camera Coordinate Transformation
447    ///
448    /// The pose is a camera-to-world SE(3) transformation: T_cw = (R, t) where:
449    /// - R ∈ SO(3): rotation from camera to world
450    /// - t ∈ ℝ³: translation of camera origin in world frame
451    ///
452    /// To transform from world to camera, we use the inverse:
453    /// ```text
454    /// p_cam = T_cw^{-1} · p_world = R^T · (p_world - t)
455    /// ```
456    ///
457    /// ## SE(3) Right Perturbation
458    ///
459    /// Right perturbation on SE(3) for δξ = [δρ; δθ] ∈ ℝ⁶:
460    /// ```text
461    /// T' = T ∘ Exp(δξ)
462    /// ```
463    ///
464    /// Where δξ = [δρ; δθ] with:
465    /// - δρ ∈ ℝ³: translation perturbation (in camera frame)
466    /// - δθ ∈ ℝ³: rotation perturbation (axis-angle in camera frame)
467    ///
468    /// ## Perturbation Effect on Transformed Point
469    ///
470    /// Under right perturbation T' = T ∘ Exp([δρ; δθ]):
471    /// ```text
472    /// R' = R · Exp(δθ) ≈ R · (I + [δθ]×)
473    /// t' ≈ t + R · δρ  (for small δθ, V(δθ) ≈ I)
474    /// ```
475    ///
476    /// Then the transformed point becomes:
477    /// ```text
478    /// p_cam' = (R')^T · (p_world - t')
479    ///        = (I - [δθ]×) · R^T · (p_world - t - R · δρ)
480    ///        ≈ (I - [δθ]×) · R^T · (p_world - t) - (I - [δθ]×) · δρ
481    ///        ≈ (I - [δθ]×) · p_cam - δρ
482    ///        = p_cam - [δθ]× · p_cam - δρ
483    ///        = p_cam + p_cam × δθ - δρ
484    ///        = p_cam + [p_cam]× · δθ - δρ
485    ///        = p_cam + [p_cam]× · δθ - δρ
486    /// ```
487    ///
488    /// Where [v]× denotes the skew-symmetric matrix (cross-product matrix).
489    ///
490    /// ## Jacobian of p_cam w.r.t. Pose Perturbation
491    ///
492    /// From the above derivation:
493    /// ```text
494    /// ∂p_cam/∂[δρ; δθ] = [-I | [p_cam]×]
495    /// ```
496    ///
497    /// This is a 3×6 matrix where:
498    /// - First 3 columns (translation): -I (identity with negative sign)
499    /// - Last 3 columns (rotation): [p_cam]× (skew-symmetric matrix of p_cam)
500    ///
501    /// ## Chain Rule
502    ///
503    /// The final Jacobian is:
504    /// ```text
505    /// ∂(u,v)/∂ξ = ∂(u,v)/∂p_cam · ∂p_cam/∂ξ
506    /// ```
507    ///
508    /// # Arguments
509    ///
510    /// * `p_world` - 3D point in world coordinate frame.
511    /// * `pose` - The camera pose in SE(3).
512    ///
513    /// # Returns
514    ///
515    /// Returns a tuple `(d_uv_d_pcam, d_pcam_d_pose)`:
516    /// - `d_uv_d_pcam`: 2×3 Jacobian of projection w.r.t. point in camera frame
517    /// - `d_pcam_d_pose`: 3×6 Jacobian of camera point w.r.t. pose perturbation
518    ///
519    /// # References
520    ///
521    /// - Barfoot & Furgale, "Associating Uncertainty with Three-Dimensional Poses for Use in Estimation Problems", IEEE Trans. Robotics 2014
522    /// - Solà et al., "A Micro Lie Theory for State Estimation in Robotics", arXiv:1812.01537, 2018
523    /// - Blanco, "A tutorial on SE(3) transformation parameterizations and on-manifold optimization", Technical Report 2010
524    ///
525    /// # Verification
526    ///
527    /// This Jacobian is verified against numerical differentiation in tests.
528    fn jacobian_pose(
529        &self,
530        p_world: &Vector3<f64>,
531        pose: &SE3,
532    ) -> (Self::PointJacobian, SMatrix<f64, 3, 6>) {
533        // World-to-camera convention: p_cam = R · p_world + t
534        let p_cam = pose.act(p_world, None, None);
535
536        let d_uv_d_pcam = self.jacobian_point(&p_cam);
537
538        // Right perturbation on T_wc:
539        //   ∂p_cam/∂δρ = R        (cols 0-2)
540        //   ∂p_cam/∂δθ = -R·[p_world]×  (cols 3-5)
541        let rotation = pose.rotation_so3().rotation_matrix();
542        let p_world_skew = skew_symmetric(p_world);
543
544        let d_pcam_d_pose = SMatrix::<f64, 3, 6>::from_fn(|r, c| {
545            if c < 3 {
546                rotation[(r, c)]
547            } else {
548                let col = c - 3;
549                -(0..3)
550                    .map(|k| rotation[(r, k)] * p_world_skew[(k, col)])
551                    .sum::<f64>()
552            }
553        });
554
555        (d_uv_d_pcam, d_pcam_d_pose)
556    }
557
558    /// Computes the Jacobian of the projection function with respect to intrinsic parameters.
559    ///
560    /// # Mathematical Derivation
561    ///
562    /// The strict BAL camera has EXACTLY 3 intrinsic parameters:
563    /// ```text
564    /// θ = [f, k1, k2]
565    /// ```
566    ///
567    /// Where:
568    /// - f: Single focal length (fx = fy = f)
569    /// - k1, k2: Radial distortion coefficients
570    /// - NO principal point (cx = cy = 0 by convention)
571    ///
572    /// ## Projection Model
573    ///
574    /// Recall the projection equations:
575    /// ```text
576    /// x_n = x / (-z),  y_n = y / (-z)
577    /// r² = x_n² + y_n²
578    /// d(r²; k1, k2) = 1 + k1·r² + k2·r⁴
579    /// x_d = x_n · d(r²; k1, k2)
580    /// y_d = y_n · d(r²; k1, k2)
581    /// u = f · x_d
582    /// v = f · y_d
583    /// ```
584    ///
585    /// ## Jacobian w.r.t. Focal Length (f)
586    ///
587    /// The focal length appears only in the final step:
588    /// ```text
589    /// ∂u/∂f = ∂(f · x_d)/∂f = x_d
590    /// ∂v/∂f = ∂(f · y_d)/∂f = y_d
591    /// ```
592    ///
593    /// ## Jacobian w.r.t. Distortion Coefficients (k1, k2)
594    ///
595    /// The distortion coefficients affect the distortion function d(r²):
596    /// ```text
597    /// ∂d/∂k1 = r²
598    /// ∂d/∂k2 = r⁴
599    /// ```
600    ///
601    /// Using the chain rule:
602    /// ```text
603    /// ∂u/∂k1 = ∂(f · x_d)/∂k1 = f · ∂x_d/∂k1
604    ///        = f · ∂(x_n · d)/∂k1
605    ///        = f · x_n · (∂d/∂k1)
606    ///        = f · x_n · r²
607    ///
608    /// ∂u/∂k2 = f · x_n · (∂d/∂k2)
609    ///        = f · x_n · r⁴
610    /// ```
611    ///
612    /// Similarly for v:
613    /// ```text
614    /// ∂v/∂k1 = f · y_n · r²
615    /// ∂v/∂k2 = f · y_n · r⁴
616    /// ```
617    ///
618    /// ## Complete Jacobian Matrix (2×3)
619    ///
620    /// ```text
621    ///         ∂/∂f    ∂/∂k1        ∂/∂k2
622    /// ∂u/∂θ = [x_d,   f·x_n·r²,   f·x_n·r⁴]
623    /// ∂v/∂θ = [y_d,   f·y_n·r²,   f·y_n·r⁴]
624    /// ```
625    ///
626    /// # Arguments
627    ///
628    /// * `p_cam` - 3D point in camera coordinate frame.
629    ///
630    /// # Returns
631    ///
632    /// Returns the 2x3 Intrinsic Jacobian matrix (w.r.t `[f, k1, k2]`).
633    ///
634    /// # References
635    ///
636    /// - Agarwal et al., "Bundle Adjustment in the Large", ECCV 2010, Section 3
637    /// - [Ceres Solver: Bundle Adjustment Tutorial](http://ceres-solver.org/nnls_tutorial.html#bundle-adjustment)
638    /// - Triggs et al., "Bundle Adjustment - A Modern Synthesis", Vision Algorithms: Theory and Practice, 2000
639    ///
640    /// # Notes
641    ///
642    /// This differs from the general `BALPinholeCamera` which has 6 parameters (fx, fy, cx, cy, k1, k2).
643    /// The strict BAL format enforces `fx=fy` and `cx=cy=0` to match the original Bundler software
644    /// and standard BAL dataset files, reducing the intrinsic dimensionality from 6 to 3.
645    ///
646    /// # Verification
647    ///
648    /// This Jacobian is verified against numerical differentiation in tests.
649    fn jacobian_intrinsics(&self, p_cam: &Vector3<f64>) -> Self::IntrinsicJacobian {
650        let inv_neg_z = -1.0 / p_cam.z;
651        let x_n = p_cam.x * inv_neg_z;
652        let y_n = p_cam.y * inv_neg_z;
653
654        // Radial distortion
655        let (k1, k2) = self.distortion_params();
656        let r2 = x_n * x_n + y_n * y_n;
657        let r4 = r2 * r2;
658        let distortion = 1.0 + k1 * r2 + k2 * r4;
659
660        let x_d = x_n * distortion;
661        let y_d = y_n * distortion;
662
663        // Jacobian ∂(u,v)/∂(f,k1,k2)
664        SMatrix::<f64, 2, 3>::new(
665            x_d,               // ∂u/∂f
666            self.f * x_n * r2, // ∂u/∂k1
667            self.f * x_n * r4, // ∂u/∂k2
668            y_d,               // ∂v/∂f
669            self.f * y_n * r2, // ∂v/∂k1
670            self.f * y_n * r4, // ∂v/∂k2
671        )
672    }
673
674    /// Unprojects a 2D image point to a 3D ray.
675    ///
676    /// # Mathematical Formula
677    ///
678    /// Iterative undistortion followed by back-projection:
679    ///
680    /// ```text
681    /// x_d = u / f
682    /// y_d = v / f
683    /// // iterative undistortion to recover x_n, y_n
684    /// ray = normalize([x_n, y_n, −1])
685    /// ```
686    ///
687    /// Uses Newton-Raphson iteration to solve the radial distortion polynomial
688    /// for undistorted normalized coordinates, then converts to a unit ray.
689    ///
690    /// # Arguments
691    ///
692    /// * `point_2d` - 2D point in image coordinates (u, v).
693    ///
694    /// # Returns
695    ///
696    /// Returns the normalized 3D ray direction.
697    fn unproject(&self, point_2d: &Vector2<f64>) -> Result<Vector3<f64>, CameraModelError> {
698        // Remove distortion and convert to ray
699        // Principal point is (0,0) for strict BAL
700        let x_d = point_2d.x / self.f;
701        let y_d = point_2d.y / self.f;
702
703        // Iterative undistortion
704        let mut x_n = x_d;
705        let mut y_n = y_d;
706
707        let (k1, k2) = self.distortion_params();
708
709        for _ in 0..5 {
710            let r2 = x_n * x_n + y_n * y_n;
711            let distortion = 1.0 + k1 * r2 + k2 * r2 * r2;
712            x_n = x_d / distortion;
713            y_n = y_d / distortion;
714        }
715
716        // BAL convention: camera looks down -Z axis
717        let norm = (1.0 + x_n * x_n + y_n * y_n).sqrt();
718        Ok(Vector3::new(x_n / norm, y_n / norm, -1.0 / norm))
719    }
720
721    /// Validates camera parameters.
722    ///
723    /// # Validation Rules
724    ///
725    /// - Focal length `f` must be positive.
726    /// - Focal length `f` must be finite.
727    /// - Distortion coefficients `k1`, `k2` must be finite.
728    ///
729    /// # Errors
730    ///
731    /// Returns [`CameraModelError`] if any parameter violates validation rules.
732    fn validate_params(&self) -> Result<(), CameraModelError> {
733        self.get_pinhole_params().validate()?;
734        self.get_distortion().validate()
735    }
736
737    /// Returns the pinhole parameters of the camera.
738    ///
739    /// Note: For strict BAL cameras, `fx = fy = f` and `cx = cy = 0`.
740    ///
741    /// # Returns
742    ///
743    /// A [`PinholeParams`] struct where `fx = fy = f` and `cx = cy = 0`.
744    fn get_pinhole_params(&self) -> PinholeParams {
745        PinholeParams {
746            fx: self.f,
747            fy: self.f,
748            cx: 0.0,
749            cy: 0.0,
750        }
751    }
752
753    /// Returns the distortion model and parameters of the camera.
754    ///
755    /// # Returns
756    ///
757    /// The [`DistortionModel`] associated with this camera (typically [`DistortionModel::Radial`] with k1, k2).
758    fn get_distortion(&self) -> DistortionModel {
759        self.distortion
760    }
761
762    /// Returns the string identifier for the camera model.
763    ///
764    /// # Returns
765    ///
766    /// The string `"bal_pinhole"`.
767    fn get_model_name(&self) -> &'static str {
768        "bal_pinhole"
769    }
770}
771
772#[cfg(test)]
773mod tests {
774    use super::*;
775
776    type TestResult = Result<(), Box<dyn std::error::Error>>;
777
778    #[test]
779    fn test_bal_strict_camera_creation() -> TestResult {
780        let pinhole = PinholeParams::new(500.0, 500.0, 0.0, 0.0)?;
781        let distortion = DistortionModel::Radial { k1: 0.4, k2: -0.3 };
782        let camera = BALPinholeCameraStrict::new(pinhole, distortion)?;
783        let (k1, k2) = camera.distortion_params();
784
785        assert_eq!(camera.f, 500.0);
786        assert_eq!(k1, 0.4);
787        assert_eq!(k2, -0.3);
788        Ok(())
789    }
790
791    #[test]
792    fn test_bal_strict_rejects_different_focal_lengths() {
793        let pinhole = PinholeParams {
794            fx: 500.0,
795            fy: 505.0, // Different from fx
796            cx: 0.0,
797            cy: 0.0,
798        };
799        let distortion = DistortionModel::Radial { k1: 0.0, k2: 0.0 };
800        let result = BALPinholeCameraStrict::new(pinhole, distortion);
801        assert!(result.is_err());
802    }
803
804    #[test]
805    fn test_bal_strict_rejects_non_zero_principal_point() {
806        let pinhole = PinholeParams {
807            fx: 500.0,
808            fy: 500.0,
809            cx: 320.0, // Non-zero
810            cy: 0.0,
811        };
812        let distortion = DistortionModel::Radial { k1: 0.0, k2: 0.0 };
813        let result = BALPinholeCameraStrict::new(pinhole, distortion);
814        assert!(result.is_err());
815    }
816
817    #[test]
818    fn test_bal_strict_projection_at_optical_axis() -> TestResult {
819        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
820        let p_cam = Vector3::new(0.0, 0.0, -1.0);
821
822        let uv = camera.project(&p_cam)?;
823
824        // Point on optical axis projects to origin (no principal point offset)
825        assert!(uv.x.abs() < 1e-10);
826        assert!(uv.y.abs() < 1e-10);
827
828        Ok(())
829    }
830
831    #[test]
832    fn test_bal_strict_projection_off_axis() -> TestResult {
833        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
834        let p_cam = Vector3::new(0.1, 0.2, -1.0);
835
836        let uv = camera.project(&p_cam)?;
837
838        // u = 500 * 0.1 = 50 (no principal point offset)
839        // v = 500 * 0.2 = 100
840        assert!((uv.x - 50.0).abs() < 1e-10);
841        assert!((uv.y - 100.0).abs() < 1e-10);
842
843        Ok(())
844    }
845
846    #[test]
847    fn test_bal_strict_from_into_traits() -> TestResult {
848        let camera = BALPinholeCameraStrict::new_no_distortion(400.0)?;
849
850        // Test conversion to DVector
851        let params: DVector<f64> = (&camera).into();
852        assert_eq!(params.len(), 3);
853        assert_eq!(params[0], 400.0);
854        assert_eq!(params[1], 0.0);
855        assert_eq!(params[2], 0.0);
856
857        // Test conversion to array
858        let arr: [f64; 3] = (&camera).into();
859        assert_eq!(arr, [400.0, 0.0, 0.0]);
860
861        // Test conversion from slice
862        let params_slice = [450.0, 0.1, 0.01];
863        let camera2 = BALPinholeCameraStrict::try_from(&params_slice[..])?;
864        let (cam2_k1, cam2_k2) = camera2.distortion_params();
865        assert_eq!(camera2.f, 450.0);
866        assert_eq!(cam2_k1, 0.1);
867        assert_eq!(cam2_k2, 0.01);
868
869        // Test conversion from array
870        let camera3 = BALPinholeCameraStrict::from([500.0, 0.2, 0.02]);
871        let (cam3_k1, cam3_k2) = camera3.distortion_params();
872        assert_eq!(camera3.f, 500.0);
873        assert_eq!(cam3_k1, 0.2);
874        assert_eq!(cam3_k2, 0.02);
875
876        Ok(())
877    }
878
879    #[test]
880    fn test_project_unproject_round_trip() -> TestResult {
881        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
882
883        // BAL uses -Z convention: points in front of camera have z < 0
884        let test_points = [
885            Vector3::new(0.1, 0.2, -1.0),
886            Vector3::new(-0.3, 0.1, -2.0),
887            Vector3::new(0.05, -0.1, -0.5),
888        ];
889
890        for p_cam in &test_points {
891            let uv = camera.project(p_cam)?;
892            let ray = camera.unproject(&uv)?;
893            let dot = ray.dot(&p_cam.normalize());
894            assert!(
895                (dot - 1.0).abs() < 1e-6,
896                "Round-trip failed: dot={dot}, expected ~1.0"
897            );
898        }
899
900        Ok(())
901    }
902
903    #[test]
904    fn test_jacobian_pose_numerical() -> TestResult {
905        use apex_manifolds::LieGroup;
906        use apex_manifolds::se3::{SE3, SE3Tangent};
907
908        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
909
910        // BAL uses -Z convention. Use a pose and world point such that
911        // pose_inv.act(p_world) has z < 0.
912        let pose = SE3::from_translation_euler(0.1, -0.05, 0.2, 0.0, 0.0, 0.0);
913        let p_world = Vector3::new(0.1, 0.05, -3.0);
914
915        let (d_uv_d_pcam, d_pcam_d_pose) = camera.jacobian_pose(&p_world, &pose);
916        let d_uv_d_pose = d_uv_d_pcam * d_pcam_d_pose;
917
918        let eps = crate::NUMERICAL_DERIVATIVE_EPS;
919
920        for i in 0..6 {
921            let mut d = [0.0f64; 6];
922            d[i] = eps;
923            let delta_plus = SE3Tangent::from_components(d[0], d[1], d[2], d[3], d[4], d[5]);
924            d[i] = -eps;
925            let delta_minus = SE3Tangent::from_components(d[0], d[1], d[2], d[3], d[4], d[5]);
926
927            // Right perturbation on T_wc: pose' = pose · Exp(δ)
928            let p_cam_plus = pose.plus(&delta_plus, None, None).act(&p_world, None, None);
929            let p_cam_minus = pose
930                .plus(&delta_minus, None, None)
931                .act(&p_world, None, None);
932
933            let uv_plus = camera.project(&p_cam_plus)?;
934            let uv_minus = camera.project(&p_cam_minus)?;
935
936            let num_deriv = (uv_plus - uv_minus) / (2.0 * eps);
937
938            for r in 0..2 {
939                let analytical = d_uv_d_pose[(r, i)];
940                let numerical = num_deriv[r];
941                assert!(
942                    analytical.is_finite(),
943                    "jacobian_pose[{r},{i}] is not finite"
944                );
945                let rel_err = (analytical - numerical).abs() / (1.0 + numerical.abs());
946                assert!(
947                    rel_err < crate::JACOBIAN_TEST_TOLERANCE,
948                    "jacobian_pose mismatch at ({r},{i}): analytical={analytical}, numerical={numerical}"
949                );
950            }
951        }
952
953        Ok(())
954    }
955
956    #[test]
957    fn test_project_returns_error_behind_camera() -> TestResult {
958        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
959        // BAL: z > 0 is behind camera
960        assert!(camera.project(&Vector3::new(0.0, 0.0, 1.0)).is_err());
961        Ok(())
962    }
963
964    #[test]
965    fn test_project_at_min_depth_boundary() -> TestResult {
966        let camera = BALPinholeCameraStrict::new_no_distortion(500.0)?;
967        // BAL: min depth is in negative-z direction
968        let p_min = Vector3::new(0.0, 0.0, -crate::MIN_DEPTH);
969        if let Ok(uv) = camera.project(&p_min) {
970            assert!(uv.x.is_finite() && uv.y.is_finite());
971        }
972        Ok(())
973    }
974}