apex_solver/linalg/mod.rs
1pub mod cholesky;
2pub mod qr;
3
4use crate::core::problem;
5use faer;
6use faer::sparse;
7use std::{collections, fmt};
8use thiserror;
9
10#[derive(Debug, Default, Clone, Copy, PartialEq, Eq)]
11pub enum LinearSolverType {
12 #[default]
13 SparseCholesky,
14 SparseQR,
15}
16
17impl fmt::Display for LinearSolverType {
18 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
19 match self {
20 LinearSolverType::SparseCholesky => write!(f, "Sparse Cholesky"),
21 LinearSolverType::SparseQR => write!(f, "Sparse QR"),
22 }
23 }
24}
25
26/// Linear algebra specific error types for apex-solver
27#[derive(Debug, Clone, thiserror::Error)]
28pub enum LinAlgError {
29 /// Matrix factorization failed (Cholesky, QR, etc.)
30 #[error("Matrix factorization failed: {0}")]
31 FactorizationFailed(String),
32
33 /// Singular or near-singular matrix detected
34 #[error("Singular matrix detected (matrix is not invertible)")]
35 SingularMatrix,
36
37 /// Matrix dimensions are incompatible
38 #[error("Matrix dimension mismatch: expected {expected}, got {actual}")]
39 DimensionMismatch { expected: String, actual: String },
40
41 /// Failed to create sparse matrix from triplets
42 #[error("Failed to create sparse matrix: {0}")]
43 SparseMatrixCreation(String),
44
45 /// Matrix format conversion failed
46 #[error("Matrix conversion failed: {0}")]
47 MatrixConversion(String),
48
49 /// Numerical instability detected (NaN, Inf, extreme condition number)
50 #[error("Numerical instability detected: {0}")]
51 NumericalInstability(String),
52
53 /// Invalid matrix operation attempted
54 #[error("Invalid matrix operation: {0}")]
55 InvalidOperation(String),
56
57 /// Linear system solve failed
58 #[error("Linear system solve failed: {0}")]
59 SolveFailed(String),
60}
61
62/// Result type for linear algebra operations
63pub type LinAlgResult<T> = Result<T, LinAlgError>;
64
65// /// Contains statistical information about the quality of the optimization solution.
66// #[derive(Debug, Clone)]
67// pub struct SolverElement {
68// /// The Hessian matrix, computed as `(J^T * W * J)`.
69// ///
70// /// This is `None` if the Hessian could not be computed.
71// pub hessian: Option<sparse::SparseColMat<usize, f64>>,
72
73// /// The gradient vector, computed as `J^T * W * r`.
74// ///
75// /// This is `None` if the gradient could not be computed.
76// pub gradient: Option<Mat<f64>>,
77
78// /// The parameter covariance matrix, computed as `(J^T * W * J)^-1`.
79// ///
80// /// This is `None` if the Hessian is singular or ill-conditioned.
81// pub covariance_matrix: Option<Mat<f64>>,
82// /// Asymptotic standard errors of the parameters.
83// ///
84// /// This is `None` if the covariance matrix could not be computed.
85// /// Each error is the square root of the corresponding diagonal element
86// /// of the covariance matrix.
87// pub standard_errors: Option<Mat<f64>>,
88// }
89
90/// Trait for sparse linear solvers that can solve both normal and augmented equations
91pub trait SparseLinearSolver {
92 /// Solve the normal equation: (J^T * J) * dx = -J^T * r
93 ///
94 /// # Errors
95 /// Returns `LinAlgError` if:
96 /// - Matrix factorization fails
97 /// - Matrix is singular or ill-conditioned
98 /// - Numerical instability is detected
99 fn solve_normal_equation(
100 &mut self,
101 residuals: &faer::Mat<f64>,
102 jacobians: &sparse::SparseColMat<usize, f64>,
103 ) -> LinAlgResult<faer::Mat<f64>>;
104
105 /// Solve the augmented equation: (J^T * J + λI) * dx = -J^T * r
106 ///
107 /// # Errors
108 /// Returns `LinAlgError` if:
109 /// - Matrix factorization fails
110 /// - Matrix is singular or ill-conditioned
111 /// - Numerical instability is detected
112 fn solve_augmented_equation(
113 &mut self,
114 residuals: &faer::Mat<f64>,
115 jacobians: &sparse::SparseColMat<usize, f64>,
116 lambda: f64,
117 ) -> LinAlgResult<faer::Mat<f64>>;
118
119 /// Get the cached Hessian matrix (J^T * J) from the last solve
120 fn get_hessian(&self) -> Option<&sparse::SparseColMat<usize, f64>>;
121
122 /// Get the cached gradient vector (J^T * r) from the last solve
123 fn get_gradient(&self) -> Option<&faer::Mat<f64>>;
124
125 /// Compute the covariance matrix (H^{-1}) by inverting the cached Hessian
126 ///
127 /// Returns a reference to the covariance matrix if successful, None otherwise.
128 /// The covariance matrix represents parameter uncertainty in the tangent space.
129 fn compute_covariance_matrix(&mut self) -> Option<&faer::Mat<f64>>;
130
131 /// Get the cached covariance matrix (H^{-1}) computed from the Hessian
132 ///
133 /// Returns None if covariance has not been computed yet.
134 fn get_covariance_matrix(&self) -> Option<&faer::Mat<f64>>;
135}
136
137pub use cholesky::SparseCholeskySolver;
138pub use qr::SparseQRSolver;
139
140/// Extract per-variable covariance blocks from the full covariance matrix.
141///
142/// Given the full covariance matrix H^{-1} (inverse of information matrix),
143/// this function extracts the diagonal blocks corresponding to each individual variable.
144///
145/// # Arguments
146/// * `full_covariance` - Full covariance matrix of size n×n (from H^{-1})
147/// * `variables` - Map of variable names to their Variable objects
148/// * `variable_index_map` - Map from variable names to their starting column index in the full matrix
149///
150/// # Returns
151/// HashMap mapping variable names to their covariance matrices in tangent space.
152/// For SE3 variables, this would be 6×6 matrices; for SE2, 3×3; etc.
153///
154pub fn extract_variable_covariances(
155 full_covariance: &faer::Mat<f64>,
156 variables: &collections::HashMap<String, problem::VariableEnum>,
157 variable_index_map: &collections::HashMap<String, usize>,
158) -> collections::HashMap<String, faer::Mat<f64>> {
159 let mut result = collections::HashMap::new();
160
161 for (var_name, var) in variables {
162 // Get the starting column/row index for this variable
163 if let Some(&start_idx) = variable_index_map.get(var_name) {
164 // Get the tangent space dimension for this variable
165 let dim = var.get_size();
166
167 // Extract the block diagonal covariance for this variable
168 // This is the block [start_idx:start_idx+dim, start_idx:start_idx+dim]
169 let mut var_cov = faer::Mat::zeros(dim, dim);
170
171 for i in 0..dim {
172 for j in 0..dim {
173 var_cov[(i, j)] = full_covariance[(start_idx + i, start_idx + j)];
174 }
175 }
176
177 result.insert(var_name.clone(), var_cov);
178 }
179 }
180
181 result
182}