use super::explicit_schur::{SchurBlockStructure, SchurOrdering, SchurPreconditioner};
use crate::core::problem::VariableEnum;
use crate::linalg::{LinAlgError, LinAlgResult, LinearSolver, SparseMode, StructureAware};
use faer::Mat;
use faer::sparse::{SparseColMat, Triplet};
use nalgebra::{DMatrix, DVector, Matrix3};
use rayon::prelude::*;
use std::collections::HashMap;
use std::ops::Mul;
#[derive(Debug, Clone)]
pub struct IterativeSchurSolver {
block_structure: Option<SchurBlockStructure>,
ordering: SchurOrdering,
max_cg_iterations: usize,
cg_tolerance: f64,
preconditioner_type: SchurPreconditioner,
landmark_block_inverses: Vec<Matrix3<f64>>,
hessian: Option<SparseColMat<usize, f64>>,
gradient: Option<Mat<f64>>,
workspace_lm: Vec<f64>, workspace_cam: Vec<f64>,
camera_to_landmark_visibility: Vec<Vec<usize>>,
}
impl IterativeSchurSolver {
pub fn new() -> Self {
Self {
block_structure: None,
ordering: SchurOrdering::default(),
max_cg_iterations: 500, cg_tolerance: 1e-9, preconditioner_type: SchurPreconditioner::SchurJacobi,
landmark_block_inverses: Vec::new(),
hessian: None,
gradient: None,
workspace_lm: Vec::new(),
workspace_cam: Vec::new(),
camera_to_landmark_visibility: Vec::new(),
}
}
pub fn with_cg_params(max_iterations: usize, tolerance: f64) -> Self {
Self {
block_structure: None,
ordering: SchurOrdering::default(),
max_cg_iterations: max_iterations,
cg_tolerance: tolerance,
preconditioner_type: SchurPreconditioner::SchurJacobi,
landmark_block_inverses: Vec::new(),
hessian: None,
gradient: None,
workspace_lm: Vec::new(),
workspace_cam: Vec::new(),
camera_to_landmark_visibility: Vec::new(),
}
}
pub fn with_config(
max_iterations: usize,
tolerance: f64,
preconditioner: SchurPreconditioner,
) -> Self {
Self {
block_structure: None,
ordering: SchurOrdering::default(),
max_cg_iterations: max_iterations,
cg_tolerance: tolerance,
preconditioner_type: preconditioner,
landmark_block_inverses: Vec::new(),
hessian: None,
gradient: None,
workspace_lm: Vec::new(),
workspace_cam: Vec::new(),
camera_to_landmark_visibility: Vec::new(),
}
}
fn init_workspaces(&mut self) {
if let Some(structure) = &self.block_structure {
let lm_dof = structure.landmark_dof;
let cam_dof = structure.camera_dof;
if self.workspace_lm.len() != lm_dof {
self.workspace_lm = vec![0.0; lm_dof];
}
if self.workspace_cam.len() != cam_dof {
self.workspace_cam = vec![0.0; cam_dof];
}
}
}
fn apply_schur_operator_fast(
&self,
x: &Mat<f64>,
result: &mut Mat<f64>,
temp_lm: &mut [f64],
temp_cam: &mut [f64],
) -> LinAlgResult<()> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let hessian = self
.hessian
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;
let symbolic = hessian.symbolic();
let (cam_start, cam_end) = structure.camera_col_range();
let (lm_start, lm_end) = structure.landmark_col_range();
let cam_dof = structure.camera_dof;
temp_lm.iter_mut().for_each(|v| *v = 0.0);
temp_cam.iter_mut().for_each(|v| *v = 0.0);
for col in cam_start..cam_end {
let local_col = col - cam_start;
let x_val = x[(local_col, 0)];
let row_indices = symbolic.row_idx_of_col_raw(col);
let col_values = hessian.val_of_col(col);
for (idx, &row) in row_indices.iter().enumerate() {
let val = col_values[idx];
if row >= cam_start && row < cam_end {
let local_row = row - cam_start;
result[(local_row, 0)] += val * x_val;
} else if row >= lm_start && row < lm_end {
let local_row = row - lm_start;
temp_lm[local_row] += val * x_val;
}
}
}
for (block_idx, (_, start_col, _)) in structure.landmark_blocks.iter().enumerate() {
let inv_block = &self.landmark_block_inverses[block_idx];
let local_start = start_col - lm_start;
let in0 = temp_lm[local_start];
let in1 = temp_lm[local_start + 1];
let in2 = temp_lm[local_start + 2];
temp_lm[local_start] =
inv_block[(0, 0)] * in0 + inv_block[(0, 1)] * in1 + inv_block[(0, 2)] * in2;
temp_lm[local_start + 1] =
inv_block[(1, 0)] * in0 + inv_block[(1, 1)] * in1 + inv_block[(1, 2)] * in2;
temp_lm[local_start + 2] =
inv_block[(2, 0)] * in0 + inv_block[(2, 1)] * in1 + inv_block[(2, 2)] * in2;
}
for col in lm_start..lm_end {
let local_col = col - lm_start;
let lm_val = temp_lm[local_col];
let row_indices = symbolic.row_idx_of_col_raw(col);
let col_values = hessian.val_of_col(col);
for (idx, &row) in row_indices.iter().enumerate() {
if row >= cam_start && row < cam_end {
let local_row = row - cam_start;
temp_cam[local_row] += col_values[idx] * lm_val;
}
}
}
for i in 0..cam_dof {
result[(i, 0)] -= temp_cam[i];
}
Ok(())
}
fn extract_camera_landmark_transpose_mvp(
&self,
hessian: &SparseColMat<usize, f64>,
x: &Mat<f64>,
) -> LinAlgResult<Mat<f64>> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let (cam_start, cam_end) = structure.camera_col_range();
let (lm_start, lm_end) = structure.landmark_col_range();
let lm_dof = structure.landmark_dof;
let mut result = Mat::<f64>::zeros(lm_dof, 1);
let symbolic = hessian.symbolic();
for col in cam_start..cam_end {
let local_col = col - cam_start;
let row_indices = symbolic.row_idx_of_col_raw(col);
let col_values = hessian.val_of_col(col);
for (idx, &row) in row_indices.iter().enumerate() {
if row >= lm_start && row < lm_end {
let local_row = row - lm_start;
result[(local_row, 0)] += col_values[idx] * x[(local_col, 0)];
}
}
}
Ok(result)
}
fn extract_camera_landmark_mvp(
&self,
hessian: &SparseColMat<usize, f64>,
x: &Mat<f64>,
) -> LinAlgResult<Mat<f64>> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let (cam_start, cam_end) = structure.camera_col_range();
let (lm_start, lm_end) = structure.landmark_col_range();
let cam_dof = structure.camera_dof;
let mut result = Mat::<f64>::zeros(cam_dof, 1);
let symbolic = hessian.symbolic();
for col in lm_start..lm_end {
let local_col = col - lm_start;
let row_indices = symbolic.row_idx_of_col_raw(col);
let col_values = hessian.val_of_col(col);
for (idx, &row) in row_indices.iter().enumerate() {
if row >= cam_start && row < cam_end {
let local_row = row - cam_start;
result[(local_row, 0)] += col_values[idx] * x[(local_col, 0)];
}
}
}
Ok(result)
}
fn apply_landmark_inverse(&self, input: &Mat<f64>, output: &mut Mat<f64>) -> LinAlgResult<()> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
for (block_idx, (_, start_col, _)) in structure.landmark_blocks.iter().enumerate() {
let inv_block = &self.landmark_block_inverses[block_idx];
let local_start = start_col - structure.landmark_col_range().0;
for i in 0..3 {
let mut sum = 0.0;
for j in 0..3 {
sum += inv_block[(i, j)] * input[(local_start + j, 0)];
}
output[(local_start + i, 0)] = sum;
}
}
Ok(())
}
fn compute_block_preconditioner(&self) -> LinAlgResult<Vec<DMatrix<f64>>> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let hessian = self
.hessian
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;
let symbolic = hessian.symbolic();
let mut precond_blocks = Vec::with_capacity(structure.camera_blocks.len());
for (_, start_col, size) in &structure.camera_blocks {
let mut block = DMatrix::<f64>::zeros(*size, *size);
for local_col in 0..*size {
let global_col = start_col + local_col;
let row_indices = symbolic.row_idx_of_col_raw(global_col);
let col_values = hessian.val_of_col(global_col);
for (idx, &global_row) in row_indices.iter().enumerate() {
if global_row >= *start_col && global_row < start_col + size {
let local_row = global_row - start_col;
block[(local_row, local_col)] = col_values[idx];
}
}
}
let inv_block = match block.clone().try_inverse() {
Some(inv) => inv,
None => {
let reg = 1e-6 * block.diagonal().iter().sum::<f64>().abs() / *size as f64;
let reg = reg.max(1e-8);
for i in 0..*size {
block[(i, i)] += reg;
}
block
.try_inverse()
.unwrap_or_else(|| DMatrix::identity(*size, *size))
}
};
precond_blocks.push(inv_block);
}
Ok(precond_blocks)
}
fn apply_block_preconditioner(
&self,
r: &Mat<f64>,
precond_blocks: &[DMatrix<f64>],
) -> LinAlgResult<Mat<f64>> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let cam_dof = structure.camera_dof;
let mut z = Mat::<f64>::zeros(cam_dof, 1);
let cam_start = structure.camera_col_range().0;
for (block_idx, (_, start_col, size)) in structure.camera_blocks.iter().enumerate() {
let local_start = start_col - cam_start;
let inv_block = &precond_blocks[block_idx];
let mut r_block = DVector::<f64>::zeros(*size);
for i in 0..*size {
r_block[i] = r[(local_start + i, 0)];
}
let z_block = inv_block * r_block;
for i in 0..*size {
z[(local_start + i, 0)] = z_block[i];
}
}
Ok(z)
}
fn compute_schur_jacobi_preconditioner(&self) -> LinAlgResult<Vec<DMatrix<f64>>> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let hessian = self
.hessian
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;
let symbolic = hessian.symbolic();
let visibility = &self.camera_to_landmark_visibility;
let precond_blocks: Vec<DMatrix<f64>> = structure
.camera_blocks
.par_iter()
.enumerate()
.map(|(cam_idx, (_, cam_col_start, cam_size))| {
let mut s_ii = DMatrix::<f64>::zeros(*cam_size, *cam_size);
for local_col in 0..*cam_size {
let global_col = cam_col_start + local_col;
let row_indices = symbolic.row_idx_of_col_raw(global_col);
let col_values = hessian.val_of_col(global_col);
for (idx, &global_row) in row_indices.iter().enumerate() {
if global_row >= *cam_col_start && global_row < cam_col_start + cam_size {
let local_row = global_row - cam_col_start;
s_ii[(local_row, local_col)] = col_values[idx];
}
}
}
let visible_landmarks = if cam_idx < visibility.len() {
&visibility[cam_idx]
} else {
&[] as &[usize]
};
for &lm_block_idx in visible_landmarks {
if lm_block_idx >= structure.landmark_blocks.len() {
continue;
}
let (_, lm_col_start, _) = &structure.landmark_blocks[lm_block_idx];
let mut h_cp = DMatrix::<f64>::zeros(*cam_size, 3);
for col_offset in 0..3 {
let global_col = lm_col_start + col_offset;
let row_indices = symbolic.row_idx_of_col_raw(global_col);
let col_values = hessian.val_of_col(global_col);
for (idx, &global_row) in row_indices.iter().enumerate() {
if global_row >= *cam_col_start && global_row < cam_col_start + cam_size
{
let local_row = global_row - cam_col_start;
h_cp[(local_row, col_offset)] = col_values[idx];
}
}
}
let hpp_inv = &self.landmark_block_inverses[lm_block_idx];
let mut temp = DMatrix::<f64>::zeros(*cam_size, 3);
for i in 0..*cam_size {
for j in 0..3 {
let mut sum = 0.0;
for k in 0..3 {
sum += h_cp[(i, k)] * hpp_inv[(k, j)];
}
temp[(i, j)] = sum;
}
}
for i in 0..*cam_size {
for j in 0..*cam_size {
let mut sum = 0.0;
for k in 0..3 {
sum += temp[(i, k)] * h_cp[(j, k)];
}
s_ii[(i, j)] -= sum;
}
}
}
match s_ii.clone().try_inverse() {
Some(inv) => inv,
None => {
let trace = s_ii.trace();
let reg = (1e-6 * trace.abs() / *cam_size as f64).max(1e-8);
for i in 0..*cam_size {
s_ii[(i, i)] += reg;
}
s_ii.try_inverse()
.unwrap_or_else(|| DMatrix::identity(*cam_size, *cam_size))
}
}
})
.collect();
Ok(precond_blocks)
}
fn solve_pcg_block(
&self,
b: &Mat<f64>,
precond_blocks: &[DMatrix<f64>],
workspace_lm: &mut [f64],
workspace_cam: &mut [f64],
) -> LinAlgResult<Mat<f64>> {
let cam_dof = b.nrows();
let mut x = Mat::<f64>::zeros(cam_dof, 1);
let mut r = b.clone();
let mut z = self.apply_block_preconditioner(&r, precond_blocks)?;
let mut p = z.clone();
let mut rz_old = 0.0;
for i in 0..cam_dof {
rz_old += r[(i, 0)] * z[(i, 0)];
}
let b_norm: f64 = (0..cam_dof)
.map(|i| b[(i, 0)] * b[(i, 0)])
.sum::<f64>()
.sqrt();
let tol = self.cg_tolerance * b_norm.max(1.0);
let mut ap = Mat::<f64>::zeros(cam_dof, 1);
for iter in 0..self.max_cg_iterations {
for i in 0..cam_dof {
ap[(i, 0)] = 0.0;
}
self.apply_schur_operator_fast(&p, &mut ap, workspace_lm, workspace_cam)?;
let mut p_ap = 0.0;
for i in 0..cam_dof {
p_ap += p[(i, 0)] * ap[(i, 0)];
}
if p_ap.abs() < 1e-20 {
tracing::debug!("PCG: p^T*A*p near zero at iteration {}", iter);
break;
}
let alpha = rz_old / p_ap;
for i in 0..cam_dof {
x[(i, 0)] += alpha * p[(i, 0)];
}
for i in 0..cam_dof {
r[(i, 0)] -= alpha * ap[(i, 0)];
}
let r_norm: f64 = (0..cam_dof)
.map(|i| r[(i, 0)] * r[(i, 0)])
.sum::<f64>()
.sqrt();
if r_norm < tol {
tracing::debug!(
"PCG converged in {} iterations (residual={:.2e})",
iter + 1,
r_norm
);
break;
}
z = self.apply_block_preconditioner(&r, precond_blocks)?;
let mut rz_new = 0.0;
for i in 0..cam_dof {
rz_new += r[(i, 0)] * z[(i, 0)];
}
if rz_old.abs() < 1e-30 {
break;
}
let beta = rz_new / rz_old;
for i in 0..cam_dof {
p[(i, 0)] = z[(i, 0)] + beta * p[(i, 0)];
}
rz_old = rz_new;
}
Ok(x)
}
fn invert_landmark_blocks(&mut self, hessian: &SparseColMat<usize, f64>) -> LinAlgResult<()> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let symbolic = hessian.symbolic();
let blocks: Vec<(usize, Matrix3<f64>)> = structure
.landmark_blocks
.iter()
.enumerate()
.map(|(i, (_, start_col, _))| {
let mut block = Matrix3::<f64>::zeros();
for local_col in 0..3 {
let global_col = start_col + local_col;
let row_indices = symbolic.row_idx_of_col_raw(global_col);
let col_values = hessian.val_of_col(global_col);
for (idx, &row) in row_indices.iter().enumerate() {
if row >= *start_col && row < start_col + 3 {
let local_row = row - start_col;
block[(local_row, local_col)] = col_values[idx];
}
}
}
(i, block)
})
.collect();
const CONDITION_THRESHOLD: f64 = 1e10;
const MIN_EIGENVALUE_THRESHOLD: f64 = 1e-12;
const REGULARIZATION_SCALE: f64 = 1e-6;
let results: Vec<Result<Matrix3<f64>, (usize, String)>> = blocks
.par_iter()
.map(|(i, block)| {
let eigenvalues = block.symmetric_eigenvalues();
let min_ev = eigenvalues.min();
let max_ev = eigenvalues.max();
if min_ev < MIN_EIGENVALUE_THRESHOLD {
let reg = REGULARIZATION_SCALE + max_ev * REGULARIZATION_SCALE;
let regularized = block + Matrix3::identity() * reg;
regularized.try_inverse().ok_or_else(|| {
(
*i,
format!("singular even with regularization (min_ev={:.2e})", min_ev),
)
})
} else if max_ev / min_ev > CONDITION_THRESHOLD {
let extra_reg = max_ev * REGULARIZATION_SCALE;
let regularized = block + Matrix3::identity() * extra_reg;
regularized.try_inverse().ok_or_else(|| {
(
*i,
format!("ill-conditioned (cond={:.2e})", max_ev / min_ev),
)
})
} else {
block
.try_inverse()
.ok_or_else(|| (*i, "singular".to_string()))
}
})
.collect();
self.landmark_block_inverses.clear();
self.landmark_block_inverses.reserve(results.len());
for result in results {
match result {
Ok(inv) => self.landmark_block_inverses.push(inv),
Err((i, msg)) => {
return Err(LinAlgError::SingularMatrix(format!(
"Landmark block {} {}",
i, msg
)));
}
}
}
Ok(())
}
fn build_visibility_index(&mut self, hessian: &SparseColMat<usize, f64>) -> LinAlgResult<()> {
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let symbolic = hessian.symbolic();
let (cam_start, cam_end) = structure.camera_col_range();
let num_cameras = structure.camera_blocks.len();
let mut cam_row_to_block: HashMap<usize, usize> = HashMap::new();
for (cam_idx, (_, start_col, size)) in structure.camera_blocks.iter().enumerate() {
for offset in 0..*size {
cam_row_to_block.insert(start_col + offset, cam_idx);
}
}
let mut visibility: Vec<Vec<usize>> = vec![Vec::new(); num_cameras];
for (lm_block_idx, (_, lm_col_start, _)) in structure.landmark_blocks.iter().enumerate() {
let global_col = *lm_col_start;
if global_col >= hessian.ncols() {
continue;
}
let row_indices = symbolic.row_idx_of_col_raw(global_col);
for &row in row_indices {
if row >= cam_start
&& row < cam_end
&& let Some(&cam_idx) = cam_row_to_block.get(&row)
{
if visibility[cam_idx].last() != Some(&lm_block_idx) {
visibility[cam_idx].push(lm_block_idx);
}
}
}
}
self.camera_to_landmark_visibility = visibility;
Ok(())
}
fn solve_with_cached_hessian(&mut self) -> LinAlgResult<Mat<f64>> {
let hessian = self
.hessian
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Hessian not cached".into()))?
.clone();
let gradient = self
.gradient
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Gradient not cached".into()))?
.clone();
let structure = self
.block_structure
.as_ref()
.ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
let cam_dof = structure.camera_dof;
let lm_dof = structure.landmark_dof;
let (cam_start, _cam_end) = structure.camera_col_range();
let (lm_start, _lm_end) = structure.landmark_col_range();
self.invert_landmark_blocks(&hessian)?;
self.build_visibility_index(&hessian)?;
let mut g_reduced = Mat::<f64>::zeros(cam_dof, 1);
for i in 0..cam_dof {
g_reduced[(i, 0)] = gradient[(cam_start + i, 0)];
}
let mut g_lm = Mat::<f64>::zeros(lm_dof, 1);
for i in 0..lm_dof {
g_lm[(i, 0)] = gradient[(lm_start + i, 0)];
}
let mut temp = Mat::<f64>::zeros(lm_dof, 1);
self.apply_landmark_inverse(&g_lm, &mut temp)?;
let correction = self.extract_camera_landmark_mvp(&hessian, &temp)?;
for i in 0..cam_dof {
g_reduced[(i, 0)] -= correction[(i, 0)];
}
self.init_workspaces();
let precond_blocks = match self.preconditioner_type {
SchurPreconditioner::SchurJacobi => {
self.compute_schur_jacobi_preconditioner()?
}
SchurPreconditioner::BlockDiagonal => {
self.compute_block_preconditioner()?
}
SchurPreconditioner::None => {
let structure = self.block_structure.as_ref().ok_or_else(|| {
LinAlgError::InvalidInput("Block structure not initialized".into())
})?;
structure
.camera_blocks
.iter()
.map(|(_, _, size)| DMatrix::identity(*size, *size))
.collect()
}
};
let mut workspace_lm = std::mem::take(&mut self.workspace_lm);
let mut workspace_cam = std::mem::take(&mut self.workspace_cam);
let delta_cam = self.solve_pcg_block(
&g_reduced,
&precond_blocks,
&mut workspace_lm,
&mut workspace_cam,
)?;
self.workspace_lm = workspace_lm;
self.workspace_cam = workspace_cam;
let hcp_t_delta_cam = self.extract_camera_landmark_transpose_mvp(&hessian, &delta_cam)?;
let mut rhs_lm = Mat::<f64>::zeros(lm_dof, 1);
for i in 0..lm_dof {
rhs_lm[(i, 0)] = g_lm[(i, 0)] - hcp_t_delta_cam[(i, 0)];
}
let mut delta_lm = Mat::<f64>::zeros(lm_dof, 1);
self.apply_landmark_inverse(&rhs_lm, &mut delta_lm)?;
let total_dof = cam_dof + lm_dof;
let mut delta = Mat::<f64>::zeros(total_dof, 1);
for i in 0..cam_dof {
delta[(cam_start + i, 0)] = delta_cam[(i, 0)];
}
for i in 0..lm_dof {
delta[(lm_start + i, 0)] = delta_lm[(i, 0)];
}
Ok(delta)
}
}
impl Default for IterativeSchurSolver {
fn default() -> Self {
Self::new()
}
}
impl StructureAware for IterativeSchurSolver {
fn initialize_structure(
&mut self,
variables: &HashMap<String, VariableEnum>,
variable_index_map: &HashMap<String, usize>,
) -> LinAlgResult<()> {
let mut structure = SchurBlockStructure::new();
for (name, variable) in variables {
let manifold_type = variable.manifold_type();
let start_col = *variable_index_map.get(name).ok_or_else(|| {
LinAlgError::InvalidInput(format!("Variable {} not in index map", name))
})?;
let size = variable.get_size();
if self.ordering.should_eliminate(name, &manifold_type, size) {
structure
.landmark_blocks
.push((name.clone(), start_col, size));
structure.landmark_dof += size;
if size != 3 {
return Err(LinAlgError::InvalidInput(format!(
"Landmark {} has DOF {}, expected 3",
name, size
)));
}
structure.num_landmarks += 1;
} else {
structure
.camera_blocks
.push((name.clone(), start_col, size));
structure.camera_dof += size;
}
}
structure.camera_blocks.sort_by_key(|(_, col, _)| *col);
structure.landmark_blocks.sort_by_key(|(_, col, _)| *col);
if structure.camera_blocks.is_empty() {
return Err(LinAlgError::InvalidInput(
"No camera variables found".into(),
));
}
if structure.landmark_blocks.is_empty() {
return Err(LinAlgError::InvalidInput(
"No landmark variables found".into(),
));
}
self.block_structure = Some(structure);
Ok(())
}
}
impl LinearSolver<SparseMode> for IterativeSchurSolver {
fn solve_normal_equation(
&mut self,
residuals: &Mat<f64>,
jacobian: &SparseColMat<usize, f64>,
) -> LinAlgResult<Mat<f64>> {
let jt = jacobian
.transpose()
.to_col_major()
.map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
let hessian = jt.mul(jacobian);
let jtr = jacobian.transpose().mul(residuals);
let mut gradient = Mat::<f64>::zeros(jtr.nrows(), 1);
for i in 0..jtr.nrows() {
gradient[(i, 0)] = -jtr[(i, 0)];
}
self.hessian = Some(hessian);
self.gradient = Some(gradient);
self.solve_with_cached_hessian()
}
fn solve_augmented_equation(
&mut self,
residuals: &Mat<f64>,
jacobian: &SparseColMat<usize, f64>,
lambda: f64,
) -> LinAlgResult<Mat<f64>> {
let jt = jacobian
.transpose()
.to_col_major()
.map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
let jtr = jt.mul(residuals);
let mut hessian = jacobian
.transpose()
.to_col_major()
.map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?
.mul(jacobian);
let n = hessian.ncols();
let symbolic = hessian.symbolic();
let mut triplets = Vec::new();
for col in 0..n {
let row_indices = symbolic.row_idx_of_col_raw(col);
let col_values = hessian.val_of_col(col);
for (idx, &row) in row_indices.iter().enumerate() {
triplets.push(Triplet::new(row, col, col_values[idx]));
}
triplets.push(Triplet::new(col, col, lambda));
}
hessian = SparseColMat::try_new_from_triplets(n, n, &triplets).map_err(|e| {
LinAlgError::InvalidInput(format!("Failed to build damped Hessian: {:?}", e))
})?;
let mut gradient = Mat::<f64>::zeros(jtr.nrows(), 1);
for i in 0..jtr.nrows() {
gradient[(i, 0)] = -jtr[(i, 0)];
}
self.hessian = Some(hessian);
self.gradient = Some(gradient.clone());
self.solve_with_cached_hessian()
}
fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>> {
self.hessian.as_ref()
}
fn get_gradient(&self) -> Option<&Mat<f64>> {
self.gradient.as_ref()
}
}
#[cfg(test)]
mod tests {
use super::*;
use crate::core::variable::Variable;
use apex_manifolds::{rn, se3};
type TestResult = Result<(), Box<dyn std::error::Error>>;
type TestSetup = (
HashMap<String, VariableEnum>,
HashMap<String, usize>,
SparseColMat<usize, f64>,
faer::Mat<f64>,
);
fn create_schur_test_setup() -> Result<TestSetup, Box<dyn std::error::Error>> {
let se3_id = DVector::from_vec(vec![1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]);
let pt_zero = DVector::from_vec(vec![0.0, 0.0, 0.0]);
let mut variables: HashMap<String, VariableEnum> = HashMap::new();
variables.insert(
"cam_0".to_string(),
VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
);
variables.insert(
"cam_1".to_string(),
VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
);
variables.insert(
"pt_0".to_string(),
VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
);
variables.insert(
"pt_1".to_string(),
VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
);
variables.insert(
"pt_2".to_string(),
VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
);
let mut variable_index_map: HashMap<String, usize> = HashMap::new();
variable_index_map.insert("cam_0".to_string(), 0);
variable_index_map.insert("cam_1".to_string(), 6);
variable_index_map.insert("pt_0".to_string(), 12);
variable_index_map.insert("pt_1".to_string(), 15);
variable_index_map.insert("pt_2".to_string(), 18);
let cam_cols = [0usize, 6];
let lm_cols = [12usize, 15, 18];
let mut triplets: Vec<Triplet<usize, usize, f64>> = Vec::new();
for (ci, &cam_col) in cam_cols.iter().enumerate() {
for (li, &lm_col) in lm_cols.iter().enumerate() {
let row_base = (ci * 3 + li) * 6;
for k in 0..6 {
triplets.push(Triplet::new(row_base + k, cam_col + k, 1.0));
triplets.push(Triplet::new(row_base + k, lm_col + (k % 3), 1.0));
}
}
}
let jacobian = SparseColMat::try_new_from_triplets(36, 21, &triplets)?;
let residuals = faer::Mat::from_fn(36, 1, |i, _| (i % 5) as f64 * 0.1);
Ok((variables, variable_index_map, jacobian, residuals))
}
#[test]
fn test_iterative_schur_creation() {
let solver = IterativeSchurSolver::new();
assert_eq!(solver.max_cg_iterations, 500);
assert_eq!(solver.cg_tolerance, 1e-9);
assert_eq!(solver.preconditioner_type, SchurPreconditioner::SchurJacobi);
}
#[test]
fn test_with_custom_params() {
let solver = IterativeSchurSolver::with_cg_params(100, 1e-8);
assert_eq!(solver.max_cg_iterations, 100);
assert_eq!(solver.cg_tolerance, 1e-8);
assert_eq!(solver.preconditioner_type, SchurPreconditioner::SchurJacobi);
}
#[test]
fn test_with_full_config() {
let solver =
IterativeSchurSolver::with_config(200, 1e-10, SchurPreconditioner::BlockDiagonal);
assert_eq!(solver.max_cg_iterations, 200);
assert_eq!(solver.cg_tolerance, 1e-10);
assert_eq!(
solver.preconditioner_type,
SchurPreconditioner::BlockDiagonal
);
}
#[test]
fn test_iterative_schur_default() {
let solver = IterativeSchurSolver::default();
assert_eq!(solver.max_cg_iterations, 500);
assert_eq!(solver.cg_tolerance, 1e-9);
assert!(solver.block_structure.is_none());
assert!(solver.hessian.is_none());
assert!(solver.landmark_block_inverses.is_empty());
}
#[test]
fn test_iterative_schur_initialize_structure() -> TestResult {
let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::new();
solver.initialize_structure(&variables, &variable_index_map)?;
let bs = solver
.block_structure
.as_ref()
.ok_or("block_structure is None")?;
assert_eq!(bs.camera_blocks.len(), 2);
assert_eq!(bs.landmark_blocks.len(), 3);
assert_eq!(bs.camera_dof, 12);
assert_eq!(bs.landmark_dof, 9);
Ok(())
}
#[test]
fn test_iterative_schur_solve_normal_equation() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
let delta =
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(delta.nrows(), 21);
assert_eq!(delta.ncols(), 1);
Ok(())
}
#[test]
fn test_iterative_schur_solve_augmented_equation() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
let delta = LinearSolver::<SparseMode>::solve_augmented_equation(
&mut solver,
&residuals,
&jacobian,
0.1,
)?;
assert_eq!(delta.nrows(), 21);
Ok(())
}
#[test]
fn test_iterative_schur_get_hessian_gradient() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
assert!(LinearSolver::<SparseMode>::get_hessian(&solver).is_none());
assert!(LinearSolver::<SparseMode>::get_gradient(&solver).is_none());
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
let h = LinearSolver::<SparseMode>::get_hessian(&solver);
let g = LinearSolver::<SparseMode>::get_gradient(&solver);
assert!(h.is_some());
assert!(g.is_some());
let h = h.ok_or("hessian is None")?;
let g = g.ok_or("gradient is None")?;
assert_eq!(h.nrows(), 21);
assert_eq!(g.nrows(), 21);
Ok(())
}
#[test]
fn test_iterative_schur_invert_landmark_blocks() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(solver.landmark_block_inverses.len(), 3);
Ok(())
}
#[test]
fn test_iterative_schur_build_visibility_index() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(solver.camera_to_landmark_visibility.len(), 2);
for cam_visibility in &solver.camera_to_landmark_visibility {
assert!(!cam_visibility.is_empty());
}
Ok(())
}
#[test]
fn test_iterative_schur_workspace_init() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(solver.workspace_lm.len(), 9); assert_eq!(solver.workspace_cam.len(), 12); Ok(())
}
#[test]
fn test_iterative_schur_block_diagonal_preconditioner() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver =
IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::BlockDiagonal);
solver.initialize_structure(&variables, &variable_index_map)?;
let delta =
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(delta.nrows(), 21);
Ok(())
}
#[test]
fn test_iterative_schur_schur_jacobi_preconditioner() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver =
IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::SchurJacobi);
solver.initialize_structure(&variables, &variable_index_map)?;
let delta =
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(delta.nrows(), 21);
Ok(())
}
#[test]
fn test_iterative_schur_no_preconditioner() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::None);
solver.initialize_structure(&variables, &variable_index_map)?;
let delta =
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
assert_eq!(delta.nrows(), 21);
Ok(())
}
#[test]
fn test_iterative_schur_augmented_lambda_effect() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut s1 = IterativeSchurSolver::with_cg_params(500, 1e-6);
s1.initialize_structure(&variables, &variable_index_map)?;
let d1 = LinearSolver::<SparseMode>::solve_augmented_equation(
&mut s1, &residuals, &jacobian, 0.001,
)?;
let mut s2 = IterativeSchurSolver::with_cg_params(500, 1e-6);
s2.initialize_structure(&variables, &variable_index_map)?;
let d2 = LinearSolver::<SparseMode>::solve_augmented_equation(
&mut s2, &residuals, &jacobian, 100.0,
)?;
let norm_diff: f64 = (0..21).map(|i| (d1[(i, 0)] - d2[(i, 0)]).powi(2)).sum();
assert!(
norm_diff > 1e-10,
"Different λ should yield different updates"
);
Ok(())
}
#[test]
fn test_iterative_schur_solve_without_init_returns_error() -> TestResult {
let triplets: Vec<Triplet<usize, usize, f64>> = vec![Triplet::new(0, 0, 1.0)];
let jacobian =
SparseColMat::try_new_from_triplets(1, 1, &triplets).map_err(|e| format!("{e:?}"))?;
let residuals = faer::Mat::from_fn(1, 1, |_, _| 1.0);
let mut solver = IterativeSchurSolver::new();
let result =
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian);
assert!(result.is_err());
Ok(())
}
#[test]
fn test_apply_landmark_inverse() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
let input = faer::Mat::from_fn(9, 1, |i, _| (i + 1) as f64);
let mut output = faer::Mat::zeros(9, 1);
solver.apply_landmark_inverse(&input, &mut output)?;
let norm: f64 = (0..9).map(|i| output[(i, 0)].powi(2)).sum::<f64>().sqrt();
assert!(
norm > 0.0,
"apply_landmark_inverse should produce non-zero output"
);
Ok(())
}
#[test]
fn test_extract_camera_landmark_transpose_mvp() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
let hessian = solver.hessian.as_ref().ok_or("hessian is None")?;
let x = faer::Mat::from_fn(12, 1, |i, _| (i as f64) * 0.1);
let result = solver.extract_camera_landmark_transpose_mvp(hessian, &x)?;
assert_eq!(result.nrows(), 9);
assert_eq!(result.ncols(), 1);
Ok(())
}
#[test]
fn test_extract_camera_landmark_mvp() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
let hessian = solver.hessian.as_ref().ok_or("hessian is None")?;
let x = faer::Mat::from_fn(9, 1, |i, _| (i as f64) * 0.1);
let result = solver.extract_camera_landmark_mvp(hessian, &x)?;
assert_eq!(result.nrows(), 12);
assert_eq!(result.ncols(), 1);
Ok(())
}
#[test]
fn test_apply_block_preconditioner() -> TestResult {
let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
let mut solver =
IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::BlockDiagonal);
solver.initialize_structure(&variables, &variable_index_map)?;
LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
let precond_blocks = solver.compute_block_preconditioner()?;
assert_eq!(precond_blocks.len(), 2);
let r = faer::Mat::from_fn(12, 1, |i, _| (i + 1) as f64);
let z = solver.apply_block_preconditioner(&r, &precond_blocks)?;
assert_eq!(z.nrows(), 12);
assert_eq!(z.ncols(), 1);
let norm: f64 = (0..12).map(|i| z[(i, 0)].powi(2)).sum::<f64>().sqrt();
assert!(norm > 0.0, "Preconditioned vector should be non-zero");
Ok(())
}
#[test]
fn test_implicit_initialize_structure_no_cameras_returns_error() {
use crate::core::variable::Variable;
use apex_manifolds::rn;
use nalgebra::DVector;
let mut variables: HashMap<String, VariableEnum> = HashMap::new();
variables.insert(
"pt_0".to_string(),
VariableEnum::Rn(Variable::new(rn::Rn::from(DVector::zeros(3)))),
);
let mut variable_index_map: HashMap<String, usize> = HashMap::new();
variable_index_map.insert("pt_0".to_string(), 0);
let mut solver = IterativeSchurSolver::new();
let result = solver.initialize_structure(&variables, &variable_index_map);
assert!(
result.is_err(),
"Expected Err when no camera variables present"
);
}
#[test]
fn test_implicit_initialize_structure_no_landmarks_returns_error() {
use crate::core::variable::Variable;
use apex_manifolds::se3;
use nalgebra::DVector;
let mut variables: HashMap<String, VariableEnum> = HashMap::new();
variables.insert(
"cam_0".to_string(),
VariableEnum::SE3(Variable::new(se3::SE3::from(DVector::from_vec(vec![
1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
])))),
);
let mut variable_index_map: HashMap<String, usize> = HashMap::new();
variable_index_map.insert("cam_0".to_string(), 0);
let mut solver = IterativeSchurSolver::new();
let result = solver.initialize_structure(&variables, &variable_index_map);
assert!(
result.is_err(),
"Expected Err when no landmark variables present"
);
}
}