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