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