Skip to main content

apex_solver/factors/
mod.rs

1//! Factor implementations for graph-based optimization problems.
2//!
3//! Factors (also called constraints or error functions) represent measurements or relationships
4//! between variables in a factor graph. Each factor computes a residual (error) vector and its
5//! Jacobian with respect to the connected variables.
6//!
7//! # Factor Graph Formulation
8//!
9//! In graph-based SLAM and bundle adjustment, the optimization problem is represented as:
10//!
11//! ```text
12//! minimize Σ_i ||r_i(x)||²
13//! ```
14//!
15//! where:
16//! - `x` is the set of variables (poses, landmarks, etc.)
17//! - `r_i(x)` is the residual function for factor i
18//! - Each factor connects one or more variables
19//!
20//! # Factor Types
21//!
22//! ## Pose Factors
23//! - **Between factors**: Relative pose constraints (SE2, SE3)
24//! - **Prior factors**: Unary constraints on single variables
25//!
26//! ## Camera Projection Factors
27//!
28//! Use [`ProjectionFactor`](camera::ProjectionFactor) with a specific [`CameraModel`](camera::CameraModel).
29//!
30//! Supported camera models:
31//! - [`PinholeCamera`](camera::PinholeCamera)
32//! - [`DoubleSphereCamera`](camera::DoubleSphereCamera)
33//! - [`EucmCamera`](camera::EucmCamera)
34//! - [`FovCamera`](camera::FovCamera)
35//! - [`KannalaBrandtCamera`](camera::KannalaBrandtCamera)
36//! - [`RadTanCamera`](camera::RadTanCamera)
37//! - [`UcmCamera`](camera::UcmCamera)
38//!
39//! # Linearization
40//!
41//! Each factor must provide a `linearize` method that computes:
42//! 1. **Residual** `r(x)`: The error at the current variable values
43//! 2. **Jacobian** `J = ∂r/∂x`: How the residual changes with each variable
44//!
45//! This information is used by the optimizer to compute parameter updates via Newton-type methods.
46
47use nalgebra::{DMatrix, DVector};
48use thiserror::Error;
49
50// Pose factors
51pub mod between_factor;
52pub mod prior_factor;
53pub mod projection_factor;
54
55pub use between_factor::BetweenFactor;
56pub use prior_factor::PriorFactor;
57pub use projection_factor::ProjectionFactor;
58
59// Optimization configuration types
60
61/// Configuration for which parameters to optimize.
62///
63/// Uses const generic booleans for compile-time optimization selection.
64///
65/// # Type Parameters
66///
67/// - `POSE`: Whether to optimize camera pose (SE3 transformation)
68/// - `LANDMARK`: Whether to optimize 3D landmark positions
69/// - `INTRINSIC`: Whether to optimize camera intrinsic parameters
70#[derive(Debug, Clone, Copy, Default)]
71pub struct OptimizeParams<const POSE: bool, const LANDMARK: bool, const INTRINSIC: bool>;
72
73impl<const P: bool, const L: bool, const I: bool> OptimizeParams<P, L, I> {
74    /// Whether to optimize camera pose
75    pub const POSE: bool = P;
76    /// Whether to optimize 3D landmarks
77    pub const LANDMARK: bool = L;
78    /// Whether to optimize camera intrinsics
79    pub const INTRINSIC: bool = I;
80}
81
82/// Bundle Adjustment: optimize pose + landmarks (intrinsics fixed).
83pub type BundleAdjustment = OptimizeParams<true, true, false>;
84
85/// Self-Calibration: optimize pose + landmarks + intrinsics.
86pub type SelfCalibration = OptimizeParams<true, true, true>;
87
88/// Only Intrinsics: optimize intrinsics (pose and landmarks fixed).
89pub type OnlyIntrinsics = OptimizeParams<false, false, true>;
90
91/// Only Pose: optimize pose (landmarks and intrinsics fixed).
92pub type OnlyPose = OptimizeParams<true, false, false>;
93
94/// Only Landmarks: optimize landmarks (pose and intrinsics fixed).
95pub type OnlyLandmarks = OptimizeParams<false, true, false>;
96
97/// Pose and Intrinsics: optimize pose + intrinsics (landmarks fixed).
98pub type PoseAndIntrinsics = OptimizeParams<true, false, true>;
99
100/// Landmarks and Intrinsics: optimize landmarks + intrinsics (pose fixed).
101pub type LandmarksAndIntrinsics = OptimizeParams<false, true, true>;
102
103// Camera module alias for backward compatibility
104// Re-exports the apex-camera-models crate as `camera` module
105pub mod camera {
106    pub use apex_camera_models::*;
107}
108
109/// Factor-specific error types for apex-solver
110#[derive(Debug, Clone, Error)]
111pub enum FactorError {
112    /// Invalid dimension mismatch between expected and actual
113    #[error("Invalid dimension: expected {expected}, got {actual}")]
114    InvalidDimension { expected: usize, actual: usize },
115
116    /// Invalid projection (point behind camera or outside valid range)
117    #[error("Invalid projection: {0}")]
118    InvalidProjection(String),
119
120    /// Jacobian computation failed
121    #[error("Jacobian computation failed: {0}")]
122    JacobianFailed(String),
123
124    /// Invalid parameter values
125    #[error("Invalid parameter values: {0}")]
126    InvalidParameters(String),
127
128    /// Numerical instability detected
129    #[error("Numerical instability: {0}")]
130    NumericalInstability(String),
131}
132
133/// Result type for factor operations
134pub type FactorResult<T> = Result<T, FactorError>;
135
136/// Trait for factor (constraint) implementations in factor graph optimization.
137///
138/// A factor represents a measurement or constraint connecting one or more variables.
139/// It computes the residual (error) and Jacobian for the current variable values,
140/// which are used by the optimizer to minimize the total cost.
141///
142/// # Implementing Custom Factors
143///
144/// To create a custom factor:
145/// 1. Implement this trait
146/// 2. Define the residual function `r(x)` (how to compute error from variable values)
147/// 3. Compute the Jacobian `J = ∂r/∂x` (analytically or numerically)
148/// 4. Return the residual dimension
149///
150/// # Thread Safety
151///
152/// Factors must be `Send + Sync` to enable parallel residual/Jacobian evaluation.
153///
154/// # Example
155///
156/// ```
157/// use apex_solver::factors::Factor;
158/// use nalgebra::{DMatrix, DVector};
159///
160/// // Simple 1D range measurement factor
161/// struct RangeFactor {
162///     measurement: f64,  // Measured distance
163/// }
164///
165/// impl Factor for RangeFactor {
166///     fn linearize(&self, params: &[DVector<f64>], compute_jacobian: bool) -> (DVector<f64>, Option<DMatrix<f64>>) {
167///         // params[0] is a 2D point [x, y]
168///         let x = params[0][0];
169///         let y = params[0][1];
170///
171///         // Residual: measured distance - actual distance
172///         let predicted_distance = (x * x + y * y).sqrt();
173///         let residual = DVector::from_vec(vec![self.measurement - predicted_distance]);
174///
175///         // Jacobian: ∂(residual)/∂[x, y]
176///         let jacobian = if compute_jacobian {
177///             Some(DMatrix::from_row_slice(1, 2, &[
178///                 -x / predicted_distance,
179///                 -y / predicted_distance,
180///             ]))
181///         } else {
182///             None
183///         };
184///
185///         (residual, jacobian)
186///     }
187///
188///     fn get_dimension(&self) -> usize { 1 }
189/// }
190/// ```
191pub trait Factor: Send + Sync {
192    /// Compute the residual and Jacobian at the given parameter values.
193    ///
194    /// # Arguments
195    ///
196    /// * `params` - Slice of variable values (one `DVector` per connected variable)
197    /// * `compute_jacobian` - Whether to compute the Jacobian matrix
198    ///
199    /// # Returns
200    ///
201    /// Tuple `(residual, jacobian)` where:
202    /// - `residual`: N-dimensional error vector
203    /// - `jacobian`: N × M matrix where M is the total DOF of all variables
204    ///
205    /// # Example
206    ///
207    /// For a between factor connecting two SE2 poses (3 DOF each):
208    /// - Input: `params = [pose1 (3×1), pose2 (3×1)]`
209    /// - Output: `(residual (3×1), jacobian (3×6))`
210    fn linearize(
211        &self,
212        params: &[DVector<f64>],
213        compute_jacobian: bool,
214    ) -> (DVector<f64>, Option<DMatrix<f64>>);
215
216    /// Get the dimension of the residual vector.
217    ///
218    /// # Returns
219    ///
220    /// Number of elements in the residual vector (number of constraints)
221    ///
222    /// # Example
223    ///
224    /// - SE2 between factor: 3 (dx, dy, dtheta)
225    /// - SE3 between factor: 6 (translation + rotation)
226    /// - Prior factor: dimension of the variable
227    fn get_dimension(&self) -> usize;
228}
229
230#[cfg(test)]
231mod tests {
232    use super::*;
233    use crate::error::ErrorLogging;
234    use nalgebra::{DMatrix, DVector, dvector};
235
236    // -------------------------------------------------------------------------
237    // OptimizeParams const generic flags — all 7 type aliases
238    // -------------------------------------------------------------------------
239
240    #[test]
241    fn test_optimize_params_bundle_adjustment_flags() {
242        const { assert!(BundleAdjustment::POSE) };
243        const { assert!(BundleAdjustment::LANDMARK) };
244        const { assert!(!BundleAdjustment::INTRINSIC) };
245    }
246
247    #[test]
248    fn test_optimize_params_self_calibration_flags() {
249        const { assert!(SelfCalibration::POSE) };
250        const { assert!(SelfCalibration::LANDMARK) };
251        const { assert!(SelfCalibration::INTRINSIC) };
252    }
253
254    #[test]
255    fn test_optimize_params_only_intrinsics_flags() {
256        const { assert!(!OnlyIntrinsics::POSE) };
257        const { assert!(!OnlyIntrinsics::LANDMARK) };
258        const { assert!(OnlyIntrinsics::INTRINSIC) };
259    }
260
261    #[test]
262    fn test_optimize_params_only_pose_flags() {
263        const { assert!(OnlyPose::POSE) };
264        const { assert!(!OnlyPose::LANDMARK) };
265        const { assert!(!OnlyPose::INTRINSIC) };
266    }
267
268    #[test]
269    fn test_optimize_params_only_landmarks_flags() {
270        const { assert!(!OnlyLandmarks::POSE) };
271        const { assert!(OnlyLandmarks::LANDMARK) };
272        const { assert!(!OnlyLandmarks::INTRINSIC) };
273    }
274
275    #[test]
276    fn test_optimize_params_pose_and_intrinsics_flags() {
277        const { assert!(PoseAndIntrinsics::POSE) };
278        const { assert!(!PoseAndIntrinsics::LANDMARK) };
279        const { assert!(PoseAndIntrinsics::INTRINSIC) };
280    }
281
282    #[test]
283    fn test_optimize_params_landmarks_and_intrinsics_flags() {
284        const { assert!(!LandmarksAndIntrinsics::POSE) };
285        const { assert!(LandmarksAndIntrinsics::LANDMARK) };
286        const { assert!(LandmarksAndIntrinsics::INTRINSIC) };
287    }
288
289    // -------------------------------------------------------------------------
290    // FactorError Display — one per variant
291    // -------------------------------------------------------------------------
292
293    #[test]
294    fn test_factor_error_invalid_dimension_display() {
295        let e = FactorError::InvalidDimension {
296            expected: 3,
297            actual: 6,
298        };
299        let s = e.to_string();
300        assert!(s.contains("3"), "{s}");
301        assert!(s.contains("6"), "{s}");
302    }
303
304    #[test]
305    fn test_factor_error_invalid_projection_display() {
306        let e = FactorError::InvalidProjection("behind camera".into());
307        assert!(e.to_string().contains("behind camera"));
308    }
309
310    #[test]
311    fn test_factor_error_jacobian_failed_display() {
312        let e = FactorError::JacobianFailed("singular".into());
313        assert!(e.to_string().contains("singular"));
314    }
315
316    #[test]
317    fn test_factor_error_invalid_parameters_display() {
318        let e = FactorError::InvalidParameters("nan detected".into());
319        assert!(e.to_string().contains("nan detected"));
320    }
321
322    #[test]
323    fn test_factor_error_numerical_instability_display() {
324        let e = FactorError::NumericalInstability("overflow".into());
325        assert!(e.to_string().contains("overflow"));
326    }
327
328    // -------------------------------------------------------------------------
329    // log() / log_with_source() return self
330    // -------------------------------------------------------------------------
331
332    #[test]
333    fn test_factor_error_log_returns_self() {
334        let e = FactorError::JacobianFailed("test_log".into());
335        let returned = e.log();
336        assert!(returned.to_string().contains("test_log"));
337    }
338
339    #[test]
340    fn test_factor_error_log_with_source_returns_self() {
341        let e = FactorError::InvalidProjection("proj_log".into());
342        let source = std::io::Error::other("src");
343        let returned = e.log_with_source(source);
344        assert!(returned.to_string().contains("proj_log"));
345    }
346
347    // -------------------------------------------------------------------------
348    // Factor trait — local implementation
349    // -------------------------------------------------------------------------
350
351    struct ConstantFactor {
352        value: f64,
353    }
354
355    impl Factor for ConstantFactor {
356        fn linearize(
357            &self,
358            params: &[DVector<f64>],
359            compute_jacobian: bool,
360        ) -> (DVector<f64>, Option<DMatrix<f64>>) {
361            let residual = dvector![params[0][0] - self.value];
362            let jacobian = if compute_jacobian {
363                Some(DMatrix::from_element(1, 1, 1.0))
364            } else {
365                None
366            };
367            (residual, jacobian)
368        }
369
370        fn get_dimension(&self) -> usize {
371            1
372        }
373    }
374
375    #[test]
376    fn test_factor_linearize_with_jacobian() {
377        let f = ConstantFactor { value: 3.0 };
378        let params = vec![dvector![5.0]];
379        let (r, j) = f.linearize(&params, true);
380        assert!((r[0] - 2.0).abs() < 1e-12);
381        assert!(j.is_some());
382        let j = j.unwrap_or_else(|| DMatrix::from_element(1, 1, 0.0));
383        assert!((j[(0, 0)] - 1.0).abs() < 1e-12);
384    }
385
386    #[test]
387    fn test_factor_linearize_without_jacobian() {
388        let f = ConstantFactor { value: 3.0 };
389        let params = vec![dvector![5.0]];
390        let (r, j) = f.linearize(&params, false);
391        assert!((r[0] - 2.0).abs() < 1e-12);
392        assert!(j.is_none());
393    }
394
395    #[test]
396    fn test_factor_get_dimension() {
397        let f = ConstantFactor { value: 0.0 };
398        assert_eq!(f.get_dimension(), 1);
399    }
400
401    // -------------------------------------------------------------------------
402    // FactorResult type alias
403    // -------------------------------------------------------------------------
404
405    #[test]
406    fn test_factor_result_ok() {
407        let r: FactorResult<f64> = Ok(1.0);
408        assert!(r.is_ok());
409    }
410
411    #[test]
412    fn test_factor_result_err() {
413        let r: FactorResult<f64> = Err(FactorError::InvalidParameters("bad".into()));
414        assert!(r.is_err());
415    }
416}