pub trait SparseLinearSolver {
// Required methods
fn solve_normal_equation(
&mut self,
residuals: &Mat<f64>,
jacobians: &SparseColMat<usize, f64>,
) -> LinAlgResult<Mat<f64>>;
fn solve_augmented_equation(
&mut self,
residuals: &Mat<f64>,
jacobians: &SparseColMat<usize, f64>,
lambda: f64,
) -> LinAlgResult<Mat<f64>>;
fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>>;
fn get_gradient(&self) -> Option<&Mat<f64>>;
fn compute_covariance_matrix(&mut self) -> Option<&Mat<f64>>;
fn get_covariance_matrix(&self) -> Option<&Mat<f64>>;
}Expand description
Trait for sparse linear solvers that can solve both normal and augmented equations
Required Methods§
Sourcefn solve_normal_equation(
&mut self,
residuals: &Mat<f64>,
jacobians: &SparseColMat<usize, f64>,
) -> LinAlgResult<Mat<f64>>
fn solve_normal_equation( &mut self, residuals: &Mat<f64>, jacobians: &SparseColMat<usize, f64>, ) -> LinAlgResult<Mat<f64>>
Solve the normal equation: (J^T * J) * dx = -J^T * r
§Errors
Returns LinAlgError if:
- Matrix factorization fails
- Matrix is singular or ill-conditioned
- Numerical instability is detected
Sourcefn solve_augmented_equation(
&mut self,
residuals: &Mat<f64>,
jacobians: &SparseColMat<usize, f64>,
lambda: f64,
) -> LinAlgResult<Mat<f64>>
fn solve_augmented_equation( &mut self, residuals: &Mat<f64>, jacobians: &SparseColMat<usize, f64>, lambda: f64, ) -> LinAlgResult<Mat<f64>>
Solve the augmented equation: (J^T * J + λI) * dx = -J^T * r
§Errors
Returns LinAlgError if:
- Matrix factorization fails
- Matrix is singular or ill-conditioned
- Numerical instability is detected
Sourcefn get_hessian(&self) -> Option<&SparseColMat<usize, f64>>
fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>>
Get the cached Hessian matrix (J^T * J) from the last solve
Sourcefn get_gradient(&self) -> Option<&Mat<f64>>
fn get_gradient(&self) -> Option<&Mat<f64>>
Get the cached gradient vector (J^T * r) from the last solve
Sourcefn compute_covariance_matrix(&mut self) -> Option<&Mat<f64>>
fn compute_covariance_matrix(&mut self) -> Option<&Mat<f64>>
Compute the covariance matrix (H^{-1}) by inverting the cached Hessian
Returns a reference to the covariance matrix if successful, None otherwise. The covariance matrix represents parameter uncertainty in the tangent space.
Sourcefn get_covariance_matrix(&self) -> Option<&Mat<f64>>
fn get_covariance_matrix(&self) -> Option<&Mat<f64>>
Get the cached covariance matrix (H^{-1}) computed from the Hessian
Returns None if covariance has not been computed yet.