pub trait StructuredSparseLinearSolver {
// Required methods
fn initialize_structure(
&mut self,
variables: &HashMap<String, VariableEnum>,
variable_index_map: &HashMap<String, usize>,
) -> LinAlgResult<()>;
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>>;
}Expand description
Trait for structured sparse linear solvers that require variable information.
This trait extends the basic sparse solver interface to support solvers that exploit problem structure (e.g., Schur complement for bundle adjustment). These solvers need access to variable information to partition the problem.
Required Methods§
Sourcefn initialize_structure(
&mut self,
variables: &HashMap<String, VariableEnum>,
variable_index_map: &HashMap<String, usize>,
) -> LinAlgResult<()>
fn initialize_structure( &mut self, variables: &HashMap<String, VariableEnum>, variable_index_map: &HashMap<String, usize>, ) -> LinAlgResult<()>
Initialize the solver’s block structure from problem variables.
This must be called before solving to set up the internal structure.
§Arguments
variables- Map of variable names to their typed instancesvariable_index_map- Map from variable names to starting column indices
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
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
Sourcefn get_hessian(&self) -> Option<&SparseColMat<usize, f64>>
fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>>
Get the cached Hessian matrix
Sourcefn get_gradient(&self) -> Option<&Mat<f64>>
fn get_gradient(&self) -> Option<&Mat<f64>>
Get the cached gradient vector