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;
49use tracing::error;
50
51// Pose factors
52pub mod between_factor;
53pub mod camera;
54pub mod prior_factor;
55pub mod projection_factor;
56
57pub use between_factor::BetweenFactor;
58pub use prior_factor::PriorFactor;
59pub use projection_factor::ProjectionFactor;
60
61/// Factor-specific error types for apex-solver
62#[derive(Debug, Clone, Error)]
63pub enum FactorError {
64 /// Invalid dimension mismatch between expected and actual
65 #[error("Invalid dimension: expected {expected}, got {actual}")]
66 InvalidDimension { expected: usize, actual: usize },
67
68 /// Invalid projection (point behind camera or outside valid range)
69 #[error("Invalid projection: {0}")]
70 InvalidProjection(String),
71
72 /// Jacobian computation failed
73 #[error("Jacobian computation failed: {0}")]
74 JacobianFailed(String),
75
76 /// Invalid parameter values
77 #[error("Invalid parameter values: {0}")]
78 InvalidParameters(String),
79
80 /// Numerical instability detected
81 #[error("Numerical instability: {0}")]
82 NumericalInstability(String),
83}
84
85impl FactorError {
86 /// Log the error with tracing::error and return self for chaining
87 ///
88 /// This method allows for a consistent error logging pattern throughout
89 /// the factors module, ensuring all errors are properly recorded.
90 ///
91 /// # Example
92 /// ```
93 /// # use apex_solver::factors::FactorError;
94 /// # fn operation() -> Result<(), FactorError> { Ok(()) }
95 /// # fn example() -> Result<(), FactorError> {
96 /// operation()
97 /// .map_err(|e| e.log())?;
98 /// # Ok(())
99 /// # }
100 /// ```
101 #[must_use]
102 pub fn log(self) -> Self {
103 error!("{}", self);
104 self
105 }
106
107 /// Log the error with the original source error for debugging context
108 ///
109 /// This method logs both the FactorError and the underlying error
110 /// from external libraries or internal operations, providing full
111 /// debugging context when errors occur.
112 ///
113 /// # Arguments
114 /// * `source_error` - The original error (must implement Debug)
115 ///
116 /// # Example
117 /// ```
118 /// # use apex_solver::factors::FactorError;
119 /// # fn compute_jacobian() -> Result<(), std::io::Error> { Ok(()) }
120 /// # fn example() -> Result<(), FactorError> {
121 /// compute_jacobian()
122 /// .map_err(|e| {
123 /// FactorError::JacobianFailed("Matrix computation failed".to_string())
124 /// .log_with_source(e)
125 /// })?;
126 /// # Ok(())
127 /// # }
128 /// ```
129 #[must_use]
130 pub fn log_with_source<E: std::fmt::Debug>(self, source_error: E) -> Self {
131 error!("{} | Source: {:?}", self, source_error);
132 self
133 }
134}
135
136/// Result type for factor operations
137pub type FactorResult<T> = Result<T, FactorError>;
138
139/// Trait for factor (constraint) implementations in factor graph optimization.
140///
141/// A factor represents a measurement or constraint connecting one or more variables.
142/// It computes the residual (error) and Jacobian for the current variable values,
143/// which are used by the optimizer to minimize the total cost.
144///
145/// # Implementing Custom Factors
146///
147/// To create a custom factor:
148/// 1. Implement this trait
149/// 2. Define the residual function `r(x)` (how to compute error from variable values)
150/// 3. Compute the Jacobian `J = ∂r/∂x` (analytically or numerically)
151/// 4. Return the residual dimension
152///
153/// # Thread Safety
154///
155/// Factors must be `Send + Sync` to enable parallel residual/Jacobian evaluation.
156///
157/// # Example
158///
159/// ```
160/// use apex_solver::factors::Factor;
161/// use nalgebra::{DMatrix, DVector};
162///
163/// // Simple 1D range measurement factor
164/// struct RangeFactor {
165/// measurement: f64, // Measured distance
166/// }
167///
168/// impl Factor for RangeFactor {
169/// fn linearize(&self, params: &[DVector<f64>], compute_jacobian: bool) -> (DVector<f64>, Option<DMatrix<f64>>) {
170/// // params[0] is a 2D point [x, y]
171/// let x = params[0][0];
172/// let y = params[0][1];
173///
174/// // Residual: measured distance - actual distance
175/// let predicted_distance = (x * x + y * y).sqrt();
176/// let residual = DVector::from_vec(vec![self.measurement - predicted_distance]);
177///
178/// // Jacobian: ∂(residual)/∂[x, y]
179/// let jacobian = if compute_jacobian {
180/// Some(DMatrix::from_row_slice(1, 2, &[
181/// -x / predicted_distance,
182/// -y / predicted_distance,
183/// ]))
184/// } else {
185/// None
186/// };
187///
188/// (residual, jacobian)
189/// }
190///
191/// fn get_dimension(&self) -> usize { 1 }
192/// }
193/// ```
194pub trait Factor: Send + Sync {
195 /// Compute the residual and Jacobian at the given parameter values.
196 ///
197 /// # Arguments
198 ///
199 /// * `params` - Slice of variable values (one `DVector` per connected variable)
200 /// * `compute_jacobian` - Whether to compute the Jacobian matrix
201 ///
202 /// # Returns
203 ///
204 /// Tuple `(residual, jacobian)` where:
205 /// - `residual`: N-dimensional error vector
206 /// - `jacobian`: N × M matrix where M is the total DOF of all variables
207 ///
208 /// # Example
209 ///
210 /// For a between factor connecting two SE2 poses (3 DOF each):
211 /// - Input: `params = [pose1 (3×1), pose2 (3×1)]`
212 /// - Output: `(residual (3×1), jacobian (3×6))`
213 fn linearize(
214 &self,
215 params: &[DVector<f64>],
216 compute_jacobian: bool,
217 ) -> (DVector<f64>, Option<DMatrix<f64>>);
218
219 /// Get the dimension of the residual vector.
220 ///
221 /// # Returns
222 ///
223 /// Number of elements in the residual vector (number of constraints)
224 ///
225 /// # Example
226 ///
227 /// - SE2 between factor: 3 (dx, dy, dtheta)
228 /// - SE3 between factor: 6 (translation + rotation)
229 /// - Prior factor: dimension of the variable
230 fn get_dimension(&self) -> usize;
231}