1use super::implicit_schur::IterativeSchurSolver;
44use crate::core::problem::VariableEnum;
45use crate::linalg::{LinAlgError, LinAlgResult, LinearSolver, SparseMode, StructureAware};
46use apex_manifolds::ManifoldType;
47use faer::sparse::{SparseColMat, Triplet};
48use faer::{
49 Mat, Side,
50 linalg::solvers::Solve,
51 sparse::linalg::solvers::{Llt, SymbolicLlt},
52};
53use nalgebra::Matrix3;
54use std::collections::HashMap;
55use tracing::{debug, info};
56
57#[derive(Debug, Clone, Copy, PartialEq, Eq, Default)]
59pub enum SchurVariant {
60 #[default]
62 Sparse,
63 Iterative,
65}
66
67#[derive(Debug, Clone, Copy, PartialEq, Eq, Default)]
69pub enum SchurPreconditioner {
70 None,
72 BlockDiagonal,
74 #[default]
77 SchurJacobi,
78}
79
80#[derive(Debug, Clone)]
82pub struct SchurOrdering {
83 pub eliminate_types: Vec<ManifoldType>,
84 pub eliminate_rn_size: Option<usize>,
87}
88
89impl Default for SchurOrdering {
90 fn default() -> Self {
91 Self {
92 eliminate_types: vec![ManifoldType::RN],
93 eliminate_rn_size: Some(3), }
95 }
96}
97
98impl SchurOrdering {
99 pub fn new() -> Self {
100 Self::default()
101 }
102
103 pub fn should_eliminate(&self, name: &str, manifold_type: &ManifoldType, size: usize) -> bool {
112 if name.starts_with("pt_") {
114 if !self.eliminate_types.contains(manifold_type) {
116 return false;
118 }
119
120 if self
122 .eliminate_rn_size
123 .is_some_and(|required_size| size != required_size)
124 {
125 return false;
127 }
128 true
129 } else {
130 false
132 }
133 }
134}
135
136#[derive(Debug, Clone)]
138pub struct SchurBlockStructure {
139 pub camera_blocks: Vec<(String, usize, usize)>,
140 pub landmark_blocks: Vec<(String, usize, usize)>,
141 pub camera_dof: usize,
142 pub landmark_dof: usize,
143 pub num_landmarks: usize,
144}
145
146impl SchurBlockStructure {
147 pub fn new() -> Self {
148 Self {
149 camera_blocks: Vec::new(),
150 landmark_blocks: Vec::new(),
151 camera_dof: 0,
152 landmark_dof: 0,
153 num_landmarks: 0,
154 }
155 }
156
157 pub fn camera_col_range(&self) -> (usize, usize) {
158 if self.camera_blocks.is_empty() {
159 (0, 0)
160 } else {
161 let start = self.camera_blocks.first().map(|b| b.1).unwrap_or(0);
163 (start, start + self.camera_dof)
164 }
165 }
166
167 pub fn landmark_col_range(&self) -> (usize, usize) {
168 if self.landmark_blocks.is_empty() {
169 (0, 0)
170 } else {
171 let start = self.landmark_blocks.first().map(|b| b.1).unwrap_or(0);
173 (start, start + self.landmark_dof)
174 }
175 }
176}
177
178impl Default for SchurBlockStructure {
179 fn default() -> Self {
180 Self::new()
181 }
182}
183
184#[derive(Debug, Clone)]
186pub struct SparseSchurComplementSolver {
187 block_structure: Option<SchurBlockStructure>,
188 ordering: SchurOrdering,
189 variant: SchurVariant,
190 preconditioner: SchurPreconditioner,
191
192 cg_max_iterations: usize,
194 cg_tolerance: f64,
195
196 hessian: Option<SparseColMat<usize, f64>>,
198 gradient: Option<Mat<f64>>,
199
200 iterative_solver: Option<IterativeSchurSolver>,
202}
203
204impl SparseSchurComplementSolver {
205 pub fn new() -> Self {
206 Self {
207 block_structure: None,
208 ordering: SchurOrdering::default(),
209 variant: SchurVariant::default(),
210 preconditioner: SchurPreconditioner::default(),
211 cg_max_iterations: 200, cg_tolerance: 1e-6, hessian: None,
214 gradient: None,
215 iterative_solver: None,
216 }
217 }
218
219 pub fn with_ordering(mut self, ordering: SchurOrdering) -> Self {
220 self.ordering = ordering;
221 self
222 }
223
224 pub fn with_variant(mut self, variant: SchurVariant) -> Self {
225 self.variant = variant;
226 self
227 }
228
229 pub fn with_preconditioner(mut self, preconditioner: SchurPreconditioner) -> Self {
230 self.preconditioner = preconditioner;
231 self
232 }
233
234 pub fn with_cg_params(mut self, max_iter: usize, tol: f64) -> Self {
235 self.cg_max_iterations = max_iter;
236 self.cg_tolerance = tol;
237 self
238 }
239
240 pub fn block_structure(&self) -> Option<&SchurBlockStructure> {
241 self.block_structure.as_ref()
242 }
243
244 fn build_block_structure(
245 &mut self,
246 variables: &HashMap<String, VariableEnum>,
247 variable_index_map: &HashMap<String, usize>,
248 ) -> LinAlgResult<()> {
249 let mut structure = SchurBlockStructure::new();
250
251 for (name, variable) in variables {
252 let start_col = *variable_index_map.get(name).ok_or_else(|| {
253 LinAlgError::InvalidInput(format!("Variable {} not found in index map", name))
254 })?;
255 let size = variable.get_size();
256 let manifold_type = variable.manifold_type();
257
258 if self.ordering.should_eliminate(name, &manifold_type, size) {
260 structure
262 .landmark_blocks
263 .push((name.clone(), start_col, size));
264 structure.landmark_dof += size;
265 structure.num_landmarks += 1;
266 } else {
267 structure
269 .camera_blocks
270 .push((name.clone(), start_col, size));
271 structure.camera_dof += size;
272 }
273 }
274
275 structure.camera_blocks.sort_by_key(|(_, col, _)| *col);
276 structure.landmark_blocks.sort_by_key(|(_, col, _)| *col);
277
278 if structure.camera_blocks.is_empty() {
279 return Err(LinAlgError::InvalidInput(
280 "No camera variables found".to_string(),
281 ));
282 }
283 if structure.landmark_blocks.is_empty() {
284 return Err(LinAlgError::InvalidInput(
285 "No landmark variables found".to_string(),
286 ));
287 }
288
289 info!("Schur complement block structure:");
291 info!(
292 " Camera blocks: {} variables, {} total DOF",
293 structure.camera_blocks.len(),
294 structure.camera_dof
295 );
296 info!(
297 " Landmark blocks: {} variables, {} total DOF",
298 structure.landmark_blocks.len(),
299 structure.landmark_dof
300 );
301 debug!(" Camera column range: {:?}", structure.camera_col_range());
302 debug!(
303 " Landmark column range: {:?}",
304 structure.landmark_col_range()
305 );
306 info!(
307 " Schur complement S size: {} × {}",
308 structure.camera_dof, structure.camera_dof
309 );
310
311 let (_cam_start, cam_end) = structure.camera_col_range();
313 let (land_start, _land_end) = structure.landmark_col_range();
314 if cam_end != land_start {
315 debug!(
316 "WARNING: Gap between camera and landmark blocks! cam_end={}, land_start={}",
317 cam_end, land_start
318 );
319 }
320
321 self.block_structure = Some(structure);
322 Ok(())
323 }
324
325 fn extract_landmark_blocks(
327 &self,
328 hessian: &SparseColMat<usize, f64>,
329 ) -> LinAlgResult<Vec<Matrix3<f64>>> {
330 let structure = self
331 .block_structure
332 .as_ref()
333 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
334
335 let mut blocks = Vec::with_capacity(structure.num_landmarks);
336 let symbolic = hessian.symbolic();
337
338 for (_, start_col, _) in &structure.landmark_blocks {
339 let mut block = Matrix3::<f64>::zeros();
340
341 for local_col in 0..3 {
342 let global_col = start_col + local_col;
343 let row_indices = symbolic.row_idx_of_col_raw(global_col);
344 let col_values = hessian.val_of_col(global_col);
345
346 for (idx, &row) in row_indices.iter().enumerate() {
347 if row >= *start_col && row < start_col + 3 {
348 let local_row = row - start_col;
349 block[(local_row, local_col)] = col_values[idx];
350 }
351 }
352 }
353
354 blocks.push(block);
355 }
356
357 Ok(blocks)
358 }
359
360 fn invert_landmark_blocks(blocks: &[Matrix3<f64>]) -> LinAlgResult<Vec<Matrix3<f64>>> {
366 Self::invert_landmark_blocks_with_lambda(blocks, 0.0)
367 }
368
369 fn invert_landmark_blocks_with_lambda(
378 blocks: &[Matrix3<f64>],
379 lambda: f64,
380 ) -> LinAlgResult<Vec<Matrix3<f64>>> {
381 const CONDITION_THRESHOLD: f64 = 1e10; const MIN_EIGENVALUE_THRESHOLD: f64 = 1e-12; const REGULARIZATION_SCALE: f64 = 1e-6; let mut ill_conditioned_count = 0;
387 let mut regularized_count = 0;
388
389 let result: LinAlgResult<Vec<Matrix3<f64>>> = blocks
390 .iter()
391 .enumerate()
392 .map(|(i, block)| {
393 let eigenvalues = block.symmetric_eigenvalues();
396 let min_ev = eigenvalues.min();
397 let max_ev = eigenvalues.max();
398
399 if min_ev < MIN_EIGENVALUE_THRESHOLD {
400 regularized_count += 1;
402 let reg = lambda.max(REGULARIZATION_SCALE) + max_ev * REGULARIZATION_SCALE;
403 let regularized = block + Matrix3::identity() * reg;
404 regularized.try_inverse().ok_or_else(|| {
405 LinAlgError::SingularMatrix(format!(
406 "Landmark block {} singular even with regularization (min_ev={:.2e})",
407 i, min_ev
408 ))
409 })
410 } else if max_ev / min_ev > CONDITION_THRESHOLD {
411 ill_conditioned_count += 1;
413 let extra_reg = max_ev * REGULARIZATION_SCALE;
414 let regularized = block + Matrix3::identity() * extra_reg;
415 regularized.try_inverse().ok_or_else(|| {
416 LinAlgError::SingularMatrix(format!(
417 "Landmark block {} ill-conditioned (cond={:.2e})",
418 i,
419 max_ev / min_ev
420 ))
421 })
422 } else {
423 block.try_inverse().ok_or_else(|| {
425 LinAlgError::SingularMatrix(format!("Landmark block {} is singular", i))
426 })
427 }
428 })
429 .collect();
430
431 if ill_conditioned_count > 0 || regularized_count > 0 {
433 debug!(
434 "Landmark block conditioning: {} ill-conditioned, {} regularized out of {}",
435 ill_conditioned_count,
436 regularized_count,
437 blocks.len()
438 );
439 }
440
441 result
442 }
443
444 fn extract_camera_block(
446 &self,
447 hessian: &SparseColMat<usize, f64>,
448 ) -> LinAlgResult<SparseColMat<usize, f64>> {
449 let structure = self
450 .block_structure
451 .as_ref()
452 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
453
454 let (cam_start, cam_end) = structure.camera_col_range();
455 let cam_size = structure.camera_dof;
456 let symbolic = hessian.symbolic();
457
458 let mut triplets = Vec::new();
459
460 for global_col in cam_start..cam_end {
461 let local_col = global_col - cam_start;
462 let row_indices = symbolic.row_idx_of_col_raw(global_col);
463 let col_values = hessian.val_of_col(global_col);
464
465 for (idx, &global_row) in row_indices.iter().enumerate() {
466 if global_row >= cam_start && global_row < cam_end {
467 let local_row = global_row - cam_start;
468 triplets.push(Triplet::new(local_row, local_col, col_values[idx]));
469 }
470 }
471 }
472
473 SparseColMat::try_new_from_triplets(cam_size, cam_size, &triplets)
474 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("H_cc: {:?}", e)))
475 }
476
477 fn extract_coupling_block(
479 &self,
480 hessian: &SparseColMat<usize, f64>,
481 ) -> LinAlgResult<SparseColMat<usize, f64>> {
482 let structure = self
483 .block_structure
484 .as_ref()
485 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
486
487 let (cam_start, cam_end) = structure.camera_col_range();
488 let (land_start, land_end) = structure.landmark_col_range();
489 let cam_size = structure.camera_dof;
490 let land_size = structure.landmark_dof;
491 let symbolic = hessian.symbolic();
492
493 let mut triplets = Vec::new();
494
495 for global_col in land_start..land_end {
496 let local_col = global_col - land_start;
497 let row_indices = symbolic.row_idx_of_col_raw(global_col);
498 let col_values = hessian.val_of_col(global_col);
499
500 for (idx, &global_row) in row_indices.iter().enumerate() {
501 if global_row >= cam_start && global_row < cam_end {
502 let local_row = global_row - cam_start;
503 triplets.push(Triplet::new(local_row, local_col, col_values[idx]));
504 }
505 }
506 }
507
508 SparseColMat::try_new_from_triplets(cam_size, land_size, &triplets)
509 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("H_cp: {:?}", e)))
510 }
511
512 fn extract_gradient_blocks(&self, gradient: &Mat<f64>) -> LinAlgResult<(Mat<f64>, Mat<f64>)> {
514 let structure = self
515 .block_structure
516 .as_ref()
517 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
518
519 let (cam_start, cam_end) = structure.camera_col_range();
520 let (land_start, land_end) = structure.landmark_col_range();
521
522 let mut g_c = Mat::zeros(structure.camera_dof, 1);
523 for i in 0..(cam_end - cam_start) {
524 g_c[(i, 0)] = gradient[(cam_start + i, 0)];
525 }
526
527 let mut g_p = Mat::zeros(structure.landmark_dof, 1);
528 for i in 0..(land_end - land_start) {
529 g_p[(i, 0)] = gradient[(land_start + i, 0)];
530 }
531
532 Ok((g_c, g_p))
533 }
534
535 fn solve_with_cholesky(
540 &self,
541 a: &SparseColMat<usize, f64>,
542 b: &Mat<f64>,
543 ) -> LinAlgResult<Mat<f64>> {
544 let sym = SymbolicLlt::try_new(a.symbolic(), Side::Lower).map_err(|e| {
545 LinAlgError::FactorizationFailed(format!("Symbolic Cholesky failed: {:?}", e))
546 })?;
547
548 match Llt::try_new_with_symbolic(sym.clone(), a.as_ref(), Side::Lower) {
550 Ok(cholesky) => return Ok(cholesky.solve(b)),
551 Err(e) => {
552 debug!(
553 "Cholesky factorization failed: {:?}. Applying regularization.",
554 e
555 );
556 }
557 }
558
559 let n = a.nrows();
561 let symbolic = a.symbolic();
562
563 let mut trace = 0.0;
565 let mut max_diag = 0.0f64;
566 for col in 0..n {
567 let row_indices = symbolic.row_idx_of_col_raw(col);
568 let col_values = a.val_of_col(col);
569 for (idx, &row) in row_indices.iter().enumerate() {
570 if row == col {
571 trace += col_values[idx];
572 max_diag = max_diag.max(col_values[idx].abs());
573 }
574 }
575 }
576
577 let avg_diag = trace / n as f64;
579 let base_reg = avg_diag.max(max_diag).max(1.0);
580
581 for attempt in 0..5 {
582 let reg = base_reg * 10.0f64.powi(attempt - 4); debug!(
584 "Cholesky attempt {}: regularization = {:.2e}",
585 attempt + 2,
586 reg
587 );
588
589 let mut triplets = Vec::with_capacity(n * 10);
590 for col in 0..n {
591 let row_indices = symbolic.row_idx_of_col_raw(col);
592 let col_values = a.val_of_col(col);
593 for (idx, &row) in row_indices.iter().enumerate() {
594 triplets.push(Triplet::new(row, col, col_values[idx]));
595 }
596 }
597
598 for i in 0..n {
599 triplets.push(Triplet::new(i, i, reg));
600 }
601
602 let a_reg = match SparseColMat::try_new_from_triplets(n, n, &triplets) {
603 Ok(m) => m,
604 Err(e) => {
605 debug!("Failed to create regularized matrix: {:?}", e);
606 continue;
607 }
608 };
609
610 let sym_reg = match SymbolicLlt::try_new(a_reg.symbolic(), Side::Lower) {
612 Ok(s) => s,
613 Err(e) => {
614 debug!("Symbolic factorization failed: {:?}", e);
615 continue;
616 }
617 };
618
619 match Llt::try_new_with_symbolic(sym_reg, a_reg.as_ref(), Side::Lower) {
620 Ok(cholesky) => {
621 debug!("Cholesky succeeded with regularization {:.2e}", reg);
622 return Ok(cholesky.solve(b));
623 }
624 Err(e) => {
625 debug!("Cholesky failed with reg {:.2e}: {:?}", reg, e);
626 }
627 }
628 }
629
630 Err(LinAlgError::SingularMatrix(format!(
631 "Schur complement singular after 5 regularization attempts (max reg = {:.2e})",
632 base_reg
633 )))
634 }
635
636 fn solve_with_pcg(&self, a: &SparseColMat<usize, f64>, b: &Mat<f64>) -> LinAlgResult<Mat<f64>> {
640 let n = b.nrows();
641 let max_iterations = self.cg_max_iterations;
642 let tolerance = self.cg_tolerance;
643
644 let symbolic = a.symbolic();
646 let mut precond = vec![1.0; n];
647 for (col, precond_val) in precond.iter_mut().enumerate().take(n) {
648 let row_indices = symbolic.row_idx_of_col_raw(col);
649 let col_values = a.val_of_col(col);
650 for (idx, &row) in row_indices.iter().enumerate() {
651 if row == col {
652 let diag = col_values[idx];
653 *precond_val = if diag.abs() > 1e-12 { 1.0 / diag } else { 1.0 };
654 break;
655 }
656 }
657 }
658
659 let mut x = Mat::<f64>::zeros(n, 1);
661
662 let mut r = b.clone();
664
665 let mut z = Mat::<f64>::zeros(n, 1);
667 for i in 0..n {
668 z[(i, 0)] = precond[i] * r[(i, 0)];
669 }
670
671 let mut p = z.clone();
672
673 let mut rz_old = 0.0;
674 for i in 0..n {
675 rz_old += r[(i, 0)] * z[(i, 0)];
676 }
677
678 let mut r_norm_init = 0.0;
680 for i in 0..n {
681 r_norm_init += r[(i, 0)] * r[(i, 0)];
682 }
683 r_norm_init = r_norm_init.sqrt();
684 let abs_tol = tolerance * r_norm_init.max(1.0);
685
686 for _iter in 0..max_iterations {
687 let mut ap = Mat::<f64>::zeros(n, 1);
689 for col in 0..n {
690 let row_indices = symbolic.row_idx_of_col_raw(col);
691 let col_values = a.val_of_col(col);
692 for (idx, &row) in row_indices.iter().enumerate() {
693 ap[(row, 0)] += col_values[idx] * p[(col, 0)];
694 }
695 }
696
697 let mut p_ap = 0.0;
699 for i in 0..n {
700 p_ap += p[(i, 0)] * ap[(i, 0)];
701 }
702
703 if p_ap.abs() < 1e-30 {
704 break;
705 }
706
707 let alpha = rz_old / p_ap;
708
709 for i in 0..n {
711 x[(i, 0)] += alpha * p[(i, 0)];
712 }
713
714 for i in 0..n {
716 r[(i, 0)] -= alpha * ap[(i, 0)];
717 }
718
719 let mut r_norm = 0.0;
721 for i in 0..n {
722 r_norm += r[(i, 0)] * r[(i, 0)];
723 }
724 r_norm = r_norm.sqrt();
725
726 if r_norm < abs_tol {
727 break;
728 }
729
730 for i in 0..n {
732 z[(i, 0)] = precond[i] * r[(i, 0)];
733 }
734
735 let mut rz_new = 0.0;
737 for i in 0..n {
738 rz_new += r[(i, 0)] * z[(i, 0)];
739 }
740
741 if rz_old.abs() < 1e-30 {
742 break;
743 }
744
745 let beta = rz_new / rz_old;
746
747 for i in 0..n {
749 p[(i, 0)] = z[(i, 0)] + beta * p[(i, 0)];
750 }
751
752 rz_old = rz_new;
753 }
754
755 Ok(x)
756 }
757
758 fn compute_schur_complement(
772 &self,
773 h_cc: &SparseColMat<usize, f64>,
774 h_cp: &SparseColMat<usize, f64>,
775 hpp_inv_blocks: &[Matrix3<f64>],
776 ) -> LinAlgResult<SparseColMat<usize, f64>> {
777 let cam_size = h_cc.nrows();
778 let h_cp_symbolic = h_cp.symbolic();
779
780 let mut s_dense = vec![0.0f64; cam_size * cam_size];
783
784 let h_cc_symbolic = h_cc.symbolic();
786 for col in 0..h_cc.ncols() {
787 let row_indices = h_cc_symbolic.row_idx_of_col_raw(col);
788 let col_values = h_cc.val_of_col(col);
789 for (idx, &row) in row_indices.iter().enumerate() {
790 s_dense[row * cam_size + col] += col_values[idx];
791 }
792 }
793
794 let mut cam_rows: Vec<usize> = Vec::with_capacity(32);
797 let mut h_cp_block: Vec<[f64; 3]> = Vec::with_capacity(32);
798 let mut contrib_block: Vec<[f64; 3]> = Vec::with_capacity(32);
799
800 for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
802 let col_start = block_idx * 3;
803
804 cam_rows.clear();
805 h_cp_block.clear();
806
807 if col_start + 2 >= h_cp.ncols() {
808 continue;
809 }
810
811 let row_indices_0 = h_cp_symbolic.row_idx_of_col_raw(col_start);
812 let col_values_0 = h_cp.val_of_col(col_start);
813 let row_indices_1 = h_cp_symbolic.row_idx_of_col_raw(col_start + 1);
814 let col_values_1 = h_cp.val_of_col(col_start + 1);
815 let row_indices_2 = h_cp_symbolic.row_idx_of_col_raw(col_start + 2);
816 let col_values_2 = h_cp.val_of_col(col_start + 2);
817
818 let mut i0 = 0;
819 let mut i1 = 0;
820 let mut i2 = 0;
821
822 while i0 < row_indices_0.len() || i1 < row_indices_1.len() || i2 < row_indices_2.len() {
823 let r0 = if i0 < row_indices_0.len() {
824 row_indices_0[i0]
825 } else {
826 usize::MAX
827 };
828 let r1 = if i1 < row_indices_1.len() {
829 row_indices_1[i1]
830 } else {
831 usize::MAX
832 };
833 let r2 = if i2 < row_indices_2.len() {
834 row_indices_2[i2]
835 } else {
836 usize::MAX
837 };
838
839 let min_row = r0.min(r1).min(r2);
840 if min_row == usize::MAX {
841 break;
842 }
843
844 let v0 = if r0 == min_row {
845 i0 += 1;
846 col_values_0[i0 - 1]
847 } else {
848 0.0
849 };
850 let v1 = if r1 == min_row {
851 i1 += 1;
852 col_values_1[i1 - 1]
853 } else {
854 0.0
855 };
856 let v2 = if r2 == min_row {
857 i2 += 1;
858 col_values_2[i2 - 1]
859 } else {
860 0.0
861 };
862
863 cam_rows.push(min_row);
864 h_cp_block.push([v0, v1, v2]);
865 }
866
867 if cam_rows.is_empty() {
868 continue;
869 }
870
871 contrib_block.clear();
872 for h_cp_row in &h_cp_block {
873 let c0 = h_cp_row[0] * hpp_inv_block[(0, 0)]
874 + h_cp_row[1] * hpp_inv_block[(1, 0)]
875 + h_cp_row[2] * hpp_inv_block[(2, 0)];
876 let c1 = h_cp_row[0] * hpp_inv_block[(0, 1)]
877 + h_cp_row[1] * hpp_inv_block[(1, 1)]
878 + h_cp_row[2] * hpp_inv_block[(2, 1)];
879 let c2 = h_cp_row[0] * hpp_inv_block[(0, 2)]
880 + h_cp_row[1] * hpp_inv_block[(1, 2)]
881 + h_cp_row[2] * hpp_inv_block[(2, 2)];
882 contrib_block.push([c0, c1, c2]);
883 }
884
885 let n_cams = cam_rows.len();
886 for i in 0..n_cams {
887 let cam_i = cam_rows[i];
888 let contrib_i = &contrib_block[i];
889 for j in 0..n_cams {
890 let cam_j = cam_rows[j];
891 let h_cp_j = &h_cp_block[j];
892 let dot = contrib_i[0] * h_cp_j[0]
893 + contrib_i[1] * h_cp_j[1]
894 + contrib_i[2] * h_cp_j[2];
895 s_dense[cam_i * cam_size + cam_j] -= dot;
896 }
897 }
898 }
899
900 for i in 0..cam_size {
904 for j in (i + 1)..cam_size {
905 let avg = (s_dense[i * cam_size + j] + s_dense[j * cam_size + i]) * 0.5;
906 s_dense[i * cam_size + j] = avg;
907 s_dense[j * cam_size + i] = avg;
908 }
909 }
910
911 let mut s_triplets: Vec<Triplet<usize, usize, f64>> = Vec::new();
914 for col in 0..cam_size {
915 for row in 0..cam_size {
916 let val = s_dense[row * cam_size + col];
917 if val.abs() > 1e-12 {
918 s_triplets.push(Triplet::new(row, col, val));
919 }
920 }
921 }
922
923 SparseColMat::try_new_from_triplets(cam_size, cam_size, &s_triplets)
924 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("Schur S: {:?}", e)))
925 }
926
927 fn compute_reduced_gradient(
929 &self,
930 g_c: &Mat<f64>,
931 g_p: &Mat<f64>,
932 h_cp: &SparseColMat<usize, f64>,
933 hpp_inv_blocks: &[Matrix3<f64>],
934 ) -> LinAlgResult<Mat<f64>> {
935 let land_size = g_p.nrows();
937 let cam_size = g_c.nrows();
938
939 let mut hpp_inv_gp = Mat::zeros(land_size, 1);
941
942 for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
943 let row_start = block_idx * 3;
944
945 let gp_block = nalgebra::Vector3::new(
946 g_p[(row_start, 0)],
947 g_p[(row_start + 1, 0)],
948 g_p[(row_start + 2, 0)],
949 );
950
951 let result = hpp_inv_block * gp_block;
952 hpp_inv_gp[(row_start, 0)] = result[0];
953 hpp_inv_gp[(row_start + 1, 0)] = result[1];
954 hpp_inv_gp[(row_start + 2, 0)] = result[2];
955 }
956
957 let mut h_cp_hpp_inv_gp = Mat::<f64>::zeros(cam_size, 1);
959 let symbolic = h_cp.symbolic();
960
961 for col in 0..h_cp.ncols() {
962 let row_indices = symbolic.row_idx_of_col_raw(col);
963 let col_values = h_cp.val_of_col(col);
964
965 for (idx, &row) in row_indices.iter().enumerate() {
966 h_cp_hpp_inv_gp[(row, 0)] += col_values[idx] * hpp_inv_gp[(col, 0)];
967 }
968 }
969
970 let mut g_reduced = Mat::zeros(cam_size, 1);
972 for i in 0..cam_size {
973 g_reduced[(i, 0)] = g_c[(i, 0)] - h_cp_hpp_inv_gp[(i, 0)];
974 }
975
976 Ok(g_reduced)
977 }
978
979 fn back_substitute(
981 &self,
982 delta_c: &Mat<f64>,
983 g_p: &Mat<f64>,
984 h_cp: &SparseColMat<usize, f64>,
985 hpp_inv_blocks: &[Matrix3<f64>],
986 ) -> LinAlgResult<Mat<f64>> {
987 let land_size = g_p.nrows();
990
991 let mut h_cp_t_delta_c = Mat::<f64>::zeros(land_size, 1);
993 let symbolic = h_cp.symbolic();
994
995 for col in 0..h_cp.ncols() {
996 let row_indices = symbolic.row_idx_of_col_raw(col);
997 let col_values = h_cp.val_of_col(col);
998
999 for (idx, &row) in row_indices.iter().enumerate() {
1000 h_cp_t_delta_c[(col, 0)] += col_values[idx] * delta_c[(row, 0)];
1001 }
1002 }
1003
1004 let mut rhs = Mat::zeros(land_size, 1);
1006 for i in 0..land_size {
1007 rhs[(i, 0)] = g_p[(i, 0)] - h_cp_t_delta_c[(i, 0)];
1008 }
1009
1010 let mut delta_p = Mat::zeros(land_size, 1);
1012
1013 for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
1014 let row_start = block_idx * 3;
1015
1016 let rhs_block = nalgebra::Vector3::new(
1017 rhs[(row_start, 0)],
1018 rhs[(row_start + 1, 0)],
1019 rhs[(row_start + 2, 0)],
1020 );
1021
1022 let result = hpp_inv_block * rhs_block;
1023 delta_p[(row_start, 0)] = result[0];
1024 delta_p[(row_start + 1, 0)] = result[1];
1025 delta_p[(row_start + 2, 0)] = result[2];
1026 }
1027
1028 Ok(delta_p)
1029 }
1030}
1031
1032impl Default for SparseSchurComplementSolver {
1033 fn default() -> Self {
1034 Self::new()
1035 }
1036}
1037
1038impl StructureAware for SparseSchurComplementSolver {
1039 fn initialize_structure(
1040 &mut self,
1041 variables: &HashMap<String, VariableEnum>,
1042 variable_index_map: &HashMap<String, usize>,
1043 ) -> LinAlgResult<()> {
1044 self.build_block_structure(variables, variable_index_map)?;
1046
1047 match self.variant {
1049 SchurVariant::Iterative => {
1050 let mut solver =
1051 IterativeSchurSolver::with_cg_params(self.cg_max_iterations, self.cg_tolerance);
1052 solver.initialize_structure(variables, variable_index_map)?;
1053 self.iterative_solver = Some(solver);
1054 }
1055 SchurVariant::Sparse => {
1056 }
1058 }
1059
1060 Ok(())
1061 }
1062}
1063
1064impl LinearSolver<SparseMode> for SparseSchurComplementSolver {
1065 fn solve_normal_equation(
1066 &mut self,
1067 residuals: &Mat<f64>,
1068 jacobian: &SparseColMat<usize, f64>,
1069 ) -> LinAlgResult<Mat<f64>> {
1070 use std::ops::Mul;
1071 let jacobians = jacobian;
1072
1073 if self.block_structure.is_none() {
1074 return Err(LinAlgError::InvalidInput(
1075 "Block structure not built. Call initialize_structure() first.".to_string(),
1076 ));
1077 }
1078
1079 let jt = jacobians
1086 .transpose()
1087 .to_col_major()
1088 .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
1089 let hessian = jt.mul(jacobians);
1090 let gradient = jacobians.transpose().mul(residuals);
1091 let mut neg_gradient = Mat::zeros(gradient.nrows(), 1);
1092 for i in 0..gradient.nrows() {
1093 neg_gradient[(i, 0)] = -gradient[(i, 0)];
1094 }
1095
1096 self.hessian = Some(hessian.clone());
1097 self.gradient = Some(gradient.clone());
1100
1101 let h_cc = self.extract_camera_block(&hessian)?;
1103 let h_cp = self.extract_coupling_block(&hessian)?;
1104 let hpp_blocks = self.extract_landmark_blocks(&hessian)?;
1105 let (g_c, g_p) = self.extract_gradient_blocks(&neg_gradient)?;
1106
1107 let hpp_inv_blocks = Self::invert_landmark_blocks(&hpp_blocks)?;
1109
1110 let s = self.compute_schur_complement(&h_cc, &h_cp, &hpp_inv_blocks)?;
1112
1113 let g_reduced = self.compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1115
1116 let delta_c = match self.variant {
1118 SchurVariant::Iterative => self.solve_with_pcg(&s, &g_reduced)?,
1119 _ => self.solve_with_cholesky(&s, &g_reduced)?,
1120 };
1121
1122 let delta_p = self.back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1124
1125 self.combine_updates(&delta_c, &delta_p)
1127 }
1128
1129 fn solve_augmented_equation(
1130 &mut self,
1131 residuals: &Mat<f64>,
1132 jacobian: &SparseColMat<usize, f64>,
1133 lambda: f64,
1134 ) -> LinAlgResult<Mat<f64>> {
1135 use std::ops::Mul;
1136 let jacobians = jacobian;
1137
1138 if self.block_structure.is_none() {
1139 return Err(LinAlgError::InvalidInput(
1140 "Block structure not built. Call initialize_structure() first.".to_string(),
1141 ));
1142 }
1143
1144 let jt = jacobians
1147 .transpose()
1148 .to_col_major()
1149 .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
1150 let hessian = jt.mul(jacobians);
1151 let gradient = jacobians.transpose().mul(residuals);
1152 let mut neg_gradient = Mat::zeros(gradient.nrows(), 1);
1153 for i in 0..gradient.nrows() {
1154 neg_gradient[(i, 0)] = -gradient[(i, 0)];
1155 }
1156
1157 self.hessian = Some(hessian.clone());
1158 self.gradient = Some(gradient.clone());
1161
1162 let h_cc = self.extract_camera_block(&hessian)?;
1164 let h_cp = self.extract_coupling_block(&hessian)?;
1165 let mut hpp_blocks = self.extract_landmark_blocks(&hessian)?;
1166 let (g_c, g_p) = self.extract_gradient_blocks(&neg_gradient)?;
1167
1168 debug!("Iteration matrices:");
1170 debug!(
1171 " Hessian (J^T*J): {} × {}",
1172 hessian.nrows(),
1173 hessian.ncols()
1174 );
1175 debug!(" H_cc (camera): {} × {}", h_cc.nrows(), h_cc.ncols());
1176 debug!(" H_cp (coupling): {} × {}", h_cp.nrows(), h_cp.ncols());
1177 debug!(" H_pp blocks: {} (3×3 each)", hpp_blocks.len());
1178
1179 let structure = self
1181 .block_structure
1182 .as_ref()
1183 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
1184 let cam_size = structure.camera_dof;
1185
1186 let mut h_cc_triplets = Vec::new();
1188 let h_cc_symbolic = h_cc.symbolic();
1189 for col in 0..h_cc.ncols() {
1190 let row_indices = h_cc_symbolic.row_idx_of_col_raw(col);
1191 let col_values = h_cc.val_of_col(col);
1192 for (idx, &row) in row_indices.iter().enumerate() {
1193 h_cc_triplets.push(Triplet::new(row, col, col_values[idx]));
1194 }
1195 }
1196 for i in 0..cam_size {
1197 if let Some(entry) = h_cc_triplets.iter_mut().find(|t| t.row == i && t.col == i) {
1198 *entry = Triplet::new(i, i, entry.val + lambda);
1199 } else {
1200 h_cc_triplets.push(Triplet::new(i, i, lambda));
1201 }
1202 }
1203 let h_cc_damped =
1204 SparseColMat::try_new_from_triplets(cam_size, cam_size, &h_cc_triplets)
1205 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("Damped H_cc: {:?}", e)))?;
1206
1207 for block in &mut hpp_blocks {
1209 block[(0, 0)] += lambda;
1210 block[(1, 1)] += lambda;
1211 block[(2, 2)] += lambda;
1212 }
1213
1214 let hpp_inv_blocks = Self::invert_landmark_blocks(&hpp_blocks)?;
1216
1217 let s = self.compute_schur_complement(&h_cc_damped, &h_cp, &hpp_inv_blocks)?;
1219
1220 let g_reduced = self.compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1222
1223 let delta_c = match self.variant {
1225 SchurVariant::Iterative => self.solve_with_pcg(&s, &g_reduced)?,
1226 _ => self.solve_with_cholesky(&s, &g_reduced)?,
1227 };
1228
1229 let delta_p = self.back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1231
1232 self.combine_updates(&delta_c, &delta_p)
1234 }
1235
1236 fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>> {
1237 self.hessian.as_ref()
1238 }
1239
1240 fn get_gradient(&self) -> Option<&Mat<f64>> {
1241 self.gradient.as_ref()
1242 }
1243}
1244
1245impl SparseSchurComplementSolver {
1247 fn combine_updates(&self, delta_c: &Mat<f64>, delta_p: &Mat<f64>) -> LinAlgResult<Mat<f64>> {
1249 let structure = self
1250 .block_structure
1251 .as_ref()
1252 .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
1253
1254 let total_dof = structure.camera_dof + structure.landmark_dof;
1255 let mut delta = Mat::zeros(total_dof, 1);
1256
1257 let (cam_start, cam_end) = structure.camera_col_range();
1258 let (land_start, land_end) = structure.landmark_col_range();
1259
1260 for i in 0..(cam_end - cam_start) {
1262 delta[(cam_start + i, 0)] = delta_c[(i, 0)];
1263 }
1264
1265 for i in 0..(land_end - land_start) {
1267 delta[(land_start + i, 0)] = delta_p[(i, 0)];
1268 }
1269
1270 debug!(
1272 "Update norms: delta_c={:.6e}, delta_p={:.6e}, combined={:.6e}",
1273 delta_c.norm_l2(),
1274 delta_p.norm_l2(),
1275 delta.norm_l2()
1276 );
1277
1278 Ok(delta)
1279 }
1280}
1281
1282#[cfg(test)]
1283mod tests {
1284 use super::*;
1285 use crate::core::variable::Variable;
1286 use apex_manifolds::{rn, se3};
1287 use nalgebra::DVector;
1288
1289 type TestResult = Result<(), Box<dyn std::error::Error>>;
1290
1291 type TestSetup = (
1293 HashMap<String, VariableEnum>,
1294 HashMap<String, usize>,
1295 SparseColMat<usize, f64>,
1296 Mat<f64>,
1297 );
1298
1299 fn create_schur_test_setup() -> Result<TestSetup, Box<dyn std::error::Error>> {
1305 let se3_id = DVector::from_vec(vec![1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]);
1306 let pt_zero = DVector::from_vec(vec![0.0, 0.0, 0.0]);
1307
1308 let mut variables: HashMap<String, VariableEnum> = HashMap::new();
1309 variables.insert(
1310 "cam_0".to_string(),
1311 VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
1312 );
1313 variables.insert(
1314 "cam_1".to_string(),
1315 VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
1316 );
1317 variables.insert(
1318 "pt_0".to_string(),
1319 VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
1320 );
1321 variables.insert(
1322 "pt_1".to_string(),
1323 VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
1324 );
1325 variables.insert(
1326 "pt_2".to_string(),
1327 VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
1328 );
1329
1330 let mut variable_index_map: HashMap<String, usize> = HashMap::new();
1333 variable_index_map.insert("cam_0".to_string(), 0);
1334 variable_index_map.insert("cam_1".to_string(), 6);
1335 variable_index_map.insert("pt_0".to_string(), 12);
1336 variable_index_map.insert("pt_1".to_string(), 15);
1337 variable_index_map.insert("pt_2".to_string(), 18);
1338
1339 let n_rows = 36;
1344 let n_cols = 21;
1345 let cam_cols = [0usize, 6];
1346 let lm_cols = [12usize, 15, 18];
1347
1348 let mut triplets: Vec<Triplet<usize, usize, f64>> = Vec::new();
1349 for (ci, &cam_col) in cam_cols.iter().enumerate() {
1350 for (li, &lm_col) in lm_cols.iter().enumerate() {
1351 let row_base = (ci * 3 + li) * 6;
1352 for k in 0..6 {
1353 triplets.push(Triplet::new(row_base + k, cam_col + k, 1.0));
1354 triplets.push(Triplet::new(row_base + k, lm_col + (k % 3), 1.0));
1355 }
1356 }
1357 }
1358
1359 let jacobian = SparseColMat::try_new_from_triplets(n_rows, n_cols, &triplets)?;
1360 let residuals = Mat::from_fn(n_rows, 1, |i, _| (i % 5) as f64 * 0.1);
1361
1362 Ok((variables, variable_index_map, jacobian, residuals))
1363 }
1364
1365 #[test]
1366 fn test_schur_ordering_shared_intrinsics() {
1367 let ordering = SchurOrdering::default();
1368
1369 assert!(ordering.should_eliminate("pt_00000", &ManifoldType::RN, 3));
1371 assert!(ordering.should_eliminate("pt_12345", &ManifoldType::RN, 3));
1372
1373 assert!(!ordering.should_eliminate("cam_0000", &ManifoldType::SE3, 6));
1375 assert!(!ordering.should_eliminate("cam_0042", &ManifoldType::SE3, 6));
1376
1377 assert!(!ordering.should_eliminate("shared_intrinsics", &ManifoldType::RN, 3));
1379
1380 assert!(!ordering.should_eliminate("intr_0000", &ManifoldType::RN, 3));
1382 assert!(!ordering.should_eliminate("intr_0042", &ManifoldType::RN, 3));
1383 }
1384
1385 #[test]
1386 fn test_schur_ordering_multiple_intrinsic_groups() {
1387 let ordering = SchurOrdering::default();
1388
1389 assert!(
1391 !ordering.should_eliminate("intr_group_0000", &ManifoldType::RN, 3),
1392 "Intrinsic group 0 should be camera parameter (not eliminated)"
1393 );
1394 assert!(
1395 !ordering.should_eliminate("intr_group_0001", &ManifoldType::RN, 3),
1396 "Intrinsic group 1 should be camera parameter (not eliminated)"
1397 );
1398 assert!(
1399 !ordering.should_eliminate("intr_group_0005", &ManifoldType::RN, 3),
1400 "Intrinsic group 5 should be camera parameter (not eliminated)"
1401 );
1402 assert!(
1403 !ordering.should_eliminate("intr_group_0042", &ManifoldType::RN, 3),
1404 "Intrinsic group 42 should be camera parameter (not eliminated)"
1405 );
1406
1407 assert!(
1409 ordering.should_eliminate("pt_00000", &ManifoldType::RN, 3),
1410 "Landmarks should still be eliminated"
1411 );
1412
1413 assert!(
1415 !ordering.should_eliminate("cam_0000", &ManifoldType::SE3, 6),
1416 "Camera poses should not be eliminated"
1417 );
1418 }
1419
1420 #[test]
1421 fn test_schur_ordering_invalid_landmark_type() {
1422 let ordering = SchurOrdering::default();
1423 assert!(
1425 !ordering.should_eliminate("pt_00000", &ManifoldType::SE3, 6),
1426 "Landmark with invalid manifold type should not be eliminated"
1427 );
1428 }
1429
1430 #[test]
1431 fn test_schur_ordering_invalid_landmark_size() {
1432 let ordering = SchurOrdering::default();
1433 assert!(
1435 !ordering.should_eliminate("pt_00000", &ManifoldType::RN, 6),
1436 "Landmark with invalid size should not be eliminated"
1437 );
1438 }
1439
1440 #[test]
1441 fn test_block_structure_creation() {
1442 let structure = SchurBlockStructure::new();
1443 assert_eq!(structure.camera_dof, 0);
1444 assert_eq!(structure.landmark_dof, 0);
1445 }
1446
1447 #[test]
1448 fn test_solver_creation() {
1449 let solver = SparseSchurComplementSolver::new();
1450 assert!(solver.block_structure.is_none());
1451 }
1452
1453 #[test]
1454 fn test_3x3_block_inversion() -> Result<(), LinAlgError> {
1455 let block = Matrix3::new(2.0, 0.0, 0.0, 0.0, 3.0, 0.0, 0.0, 0.0, 4.0);
1456 let inv = SparseSchurComplementSolver::invert_landmark_blocks(&[block])?;
1457 assert!((inv[0][(0, 0)] - 0.5).abs() < 1e-10);
1458 Ok(())
1459 }
1460
1461 #[test]
1462 fn test_schur_variants() {
1463 let solver = SparseSchurComplementSolver::new()
1464 .with_variant(SchurVariant::Iterative)
1465 .with_preconditioner(SchurPreconditioner::BlockDiagonal)
1466 .with_cg_params(100, 1e-8);
1467
1468 assert_eq!(solver.cg_max_iterations, 100);
1469 assert!((solver.cg_tolerance - 1e-8).abs() < 1e-12);
1470 }
1471
1472 #[test]
1473 fn test_compute_schur_complement_known_matrix() -> Result<(), LinAlgError> {
1474 use faer::sparse::Triplet;
1475
1476 let solver = SparseSchurComplementSolver::new();
1477
1478 let h_cc_triplets = vec![Triplet::new(0, 0, 4.0), Triplet::new(1, 1, 5.0)];
1480 let h_cc = SparseColMat::try_new_from_triplets(2, 2, &h_cc_triplets)
1481 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("{e:?}")))?;
1482
1483 let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 2.0)];
1485 let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1486 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("{e:?}")))?;
1487
1488 let hpp_inv = vec![Matrix3::new(0.5, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.5)];
1490
1491 let s = solver.compute_schur_complement(&h_cc, &h_cp, &hpp_inv)?;
1502
1503 assert_eq!(s.nrows(), 2);
1504 assert_eq!(s.ncols(), 2);
1505 assert!((s[(0, 0)] - 3.5).abs() < 1e-10, "S(0,0) = {}", s[(0, 0)]);
1513 assert!((s[(1, 1)] - 3.0).abs() < 1e-10, "S(1,1) = {}", s[(1, 1)]);
1514 Ok(())
1515 }
1516
1517 #[test]
1518 fn test_back_substitute() -> Result<(), LinAlgError> {
1519 use faer::sparse::Triplet;
1520
1521 let solver = SparseSchurComplementSolver::new();
1522
1523 let delta_c = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); let g_p = Mat::from_fn(3, 1, |i, _| (i + 1) as f64); let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 1.0)];
1529 let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1530 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("{e:?}")))?;
1531
1532 let hpp_inv = vec![Matrix3::identity()];
1534
1535 let delta_p = solver.back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv)?;
1540
1541 assert_eq!(delta_p.nrows(), 3);
1542 assert!((delta_p[(0, 0)]).abs() < 1e-10);
1543 assert!((delta_p[(1, 0)]).abs() < 1e-10);
1544 assert!((delta_p[(2, 0)] - 3.0).abs() < 1e-10);
1545 Ok(())
1546 }
1547
1548 #[test]
1549 fn test_compute_reduced_gradient() -> Result<(), LinAlgError> {
1550 use faer::sparse::Triplet;
1551
1552 let solver = SparseSchurComplementSolver::new();
1553
1554 let g_c = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); let g_p = Mat::from_fn(3, 1, |i, _| (i + 1) as f64); let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 1.0)];
1560 let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1561 .map_err(|e| LinAlgError::SparseMatrixCreation(format!("{e:?}")))?;
1562
1563 let hpp_inv = vec![Matrix3::new(2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0)];
1565
1566 let g_reduced = solver.compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv)?;
1571
1572 assert_eq!(g_reduced.nrows(), 2);
1573 assert!((g_reduced[(0, 0)] + 1.0).abs() < 1e-10);
1574 assert!((g_reduced[(1, 0)] + 2.0).abs() < 1e-10);
1575 Ok(())
1576 }
1577
1578 #[test]
1584 fn test_solver_default() {
1585 let solver = SparseSchurComplementSolver::default();
1586 assert!(solver.block_structure.is_none());
1587 assert!(solver.hessian.is_none());
1588 assert!(solver.gradient.is_none());
1589 }
1590
1591 #[test]
1593 fn test_block_structure_default() {
1594 let s = SchurBlockStructure::default();
1595 assert!(s.camera_blocks.is_empty());
1596 assert!(s.landmark_blocks.is_empty());
1597 assert_eq!(s.camera_dof, 0);
1598 assert_eq!(s.landmark_dof, 0);
1599 }
1600
1601 #[test]
1603 fn test_block_structure_col_ranges() {
1604 let mut s = SchurBlockStructure::new();
1605 assert_eq!(s.camera_col_range(), (0, 0));
1607 assert_eq!(s.landmark_col_range(), (0, 0));
1608
1609 s.camera_blocks.push(("cam_0".to_string(), 0, 6));
1611 s.camera_dof = 6;
1612 s.landmark_blocks.push(("pt_0".to_string(), 6, 3));
1613 s.landmark_dof = 3;
1614
1615 assert_eq!(s.camera_col_range(), (0, 6));
1616 assert_eq!(s.landmark_col_range(), (6, 9));
1617 }
1618
1619 #[test]
1621 fn test_block_structure_getter() -> TestResult {
1622 let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
1623 let mut solver = SparseSchurComplementSolver::new();
1624
1625 assert!(solver.block_structure().is_none());
1626 solver.initialize_structure(&variables, &variable_index_map)?;
1627 assert!(solver.block_structure().is_some());
1628 Ok(())
1629 }
1630
1631 #[test]
1633 fn test_with_ordering_builder() {
1634 let ordering = SchurOrdering {
1635 eliminate_types: vec![ManifoldType::RN],
1636 eliminate_rn_size: Some(3),
1637 };
1638 let solver = SparseSchurComplementSolver::new().with_ordering(ordering);
1639 assert_eq!(solver.ordering.eliminate_rn_size, Some(3));
1640 }
1641
1642 #[test]
1647 fn test_invert_landmark_blocks_with_lambda() -> TestResult {
1648 let block = Matrix3::new(2.0, 0.0, 0.0, 0.0, 3.0, 0.0, 0.0, 0.0, 4.0);
1650
1651 let inv = SparseSchurComplementSolver::invert_landmark_blocks_with_lambda(&[block], 0.0)?;
1653 assert_eq!(inv.len(), 1);
1654 assert!((inv[0][(0, 0)] - 0.5).abs() < 1e-10);
1655 assert!((inv[0][(1, 1)] - 1.0 / 3.0).abs() < 1e-10);
1656 assert!((inv[0][(2, 2)] - 0.25).abs() < 1e-10);
1657
1658 let inv_lam =
1660 SparseSchurComplementSolver::invert_landmark_blocks_with_lambda(&[block], 1.0)?;
1661 assert!((inv_lam[0][(0, 0)] - 0.5).abs() < 1e-10);
1662 Ok(())
1663 }
1664
1665 #[test]
1667 fn test_explicit_schur_initialize_structure() -> TestResult {
1668 let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
1669 let mut solver = SparseSchurComplementSolver::new();
1670 solver.initialize_structure(&variables, &variable_index_map)?;
1671
1672 let bs = solver.block_structure().ok_or("block_structure is None")?;
1673 assert_eq!(bs.camera_blocks.len(), 2);
1674 assert_eq!(bs.landmark_blocks.len(), 3);
1675 assert_eq!(bs.camera_dof, 12); assert_eq!(bs.landmark_dof, 9); Ok(())
1678 }
1679
1680 #[test]
1682 fn test_extract_gradient_blocks() -> TestResult {
1683 let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
1684 let mut solver = SparseSchurComplementSolver::new();
1685 solver.initialize_structure(&variables, &variable_index_map)?;
1686
1687 let gradient = Mat::from_fn(21, 1, |i, _| i as f64);
1689 let (g_c, g_p) = solver.extract_gradient_blocks(&gradient)?;
1690
1691 assert_eq!(g_c.nrows(), 12); assert_eq!(g_p.nrows(), 9); Ok(())
1694 }
1695
1696 #[test]
1698 fn test_explicit_schur_solve_normal_equation() -> TestResult {
1699 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1700 let mut solver = SparseSchurComplementSolver::new().with_variant(SchurVariant::Sparse);
1701 solver.initialize_structure(&variables, &variable_index_map)?;
1702
1703 let delta =
1704 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1705 assert_eq!(delta.nrows(), 21);
1706 assert_eq!(delta.ncols(), 1);
1707 Ok(())
1708 }
1709
1710 #[test]
1712 fn test_explicit_schur_solve_augmented_equation() -> TestResult {
1713 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1714 let mut solver = SparseSchurComplementSolver::new().with_variant(SchurVariant::Sparse);
1715 solver.initialize_structure(&variables, &variable_index_map)?;
1716
1717 let delta = LinearSolver::<SparseMode>::solve_augmented_equation(
1718 &mut solver,
1719 &residuals,
1720 &jacobian,
1721 0.1,
1722 )?;
1723 assert_eq!(delta.nrows(), 21);
1724 Ok(())
1725 }
1726
1727 #[test]
1729 fn test_explicit_schur_solve_iterative_variant() -> TestResult {
1730 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1731 let mut solver = SparseSchurComplementSolver::new()
1732 .with_variant(SchurVariant::Iterative)
1733 .with_cg_params(200, 1e-6);
1734 solver.initialize_structure(&variables, &variable_index_map)?;
1735
1736 let delta =
1737 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1738 assert_eq!(delta.nrows(), 21);
1739 Ok(())
1740 }
1741
1742 #[test]
1744 fn test_explicit_schur_get_hessian_gradient() -> TestResult {
1745 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1746 let mut solver = SparseSchurComplementSolver::new();
1747 solver.initialize_structure(&variables, &variable_index_map)?;
1748
1749 assert!(LinearSolver::<SparseMode>::get_hessian(&solver).is_none());
1750 assert!(LinearSolver::<SparseMode>::get_gradient(&solver).is_none());
1751
1752 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1753
1754 let h = LinearSolver::<SparseMode>::get_hessian(&solver);
1755 let g = LinearSolver::<SparseMode>::get_gradient(&solver);
1756 assert!(h.is_some());
1757 assert!(g.is_some());
1758 let h = h.ok_or("hessian is None")?;
1759 let g = g.ok_or("gradient is None")?;
1760 assert_eq!(h.nrows(), 21);
1761 assert_eq!(g.nrows(), 21);
1762 Ok(())
1763 }
1764
1765 #[test]
1767 fn test_explicit_schur_augmented_lambda_effect() -> TestResult {
1768 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1769
1770 let mut solver1 = SparseSchurComplementSolver::new();
1771 solver1.initialize_structure(&variables, &variable_index_map)?;
1772 let delta1 = LinearSolver::<SparseMode>::solve_augmented_equation(
1773 &mut solver1,
1774 &residuals,
1775 &jacobian,
1776 0.001,
1777 )?;
1778
1779 let mut solver2 = SparseSchurComplementSolver::new();
1780 solver2.initialize_structure(&variables, &variable_index_map)?;
1781 let delta2 = LinearSolver::<SparseMode>::solve_augmented_equation(
1782 &mut solver2,
1783 &residuals,
1784 &jacobian,
1785 100.0,
1786 )?;
1787
1788 let norm_diff: f64 = (0..21)
1790 .map(|i| (delta1[(i, 0)] - delta2[(i, 0)]).powi(2))
1791 .sum();
1792 assert!(
1793 norm_diff > 1e-10,
1794 "Different λ should yield different updates"
1795 );
1796 Ok(())
1797 }
1798
1799 #[test]
1801 fn test_combine_updates() -> TestResult {
1802 let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
1803 let mut solver = SparseSchurComplementSolver::new();
1804 solver.initialize_structure(&variables, &variable_index_map)?;
1805
1806 let delta_c = Mat::from_fn(12, 1, |_, _| 1.0);
1808 let delta_p = Mat::from_fn(9, 1, |_, _| 2.0);
1809
1810 let combined = solver.combine_updates(&delta_c, &delta_p)?;
1811 assert_eq!(combined.nrows(), 21);
1812
1813 for i in 0..12 {
1815 assert!((combined[(i, 0)] - 1.0).abs() < 1e-10);
1816 }
1817 for i in 12..21 {
1819 assert!((combined[(i, 0)] - 2.0).abs() < 1e-10);
1820 }
1821 Ok(())
1822 }
1823
1824 #[test]
1826 fn test_explicit_schur_solve_without_init_returns_error() -> TestResult {
1827 let triplets: Vec<Triplet<usize, usize, f64>> = vec![Triplet::new(0, 0, 1.0)];
1828 let jacobian =
1829 SparseColMat::try_new_from_triplets(1, 1, &triplets).map_err(|e| format!("{e:?}"))?;
1830 let residuals = Mat::from_fn(1, 1, |_, _| 1.0);
1831 let mut solver = SparseSchurComplementSolver::new();
1832
1833 let result =
1834 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian);
1835 assert!(result.is_err());
1836 Ok(())
1837 }
1838
1839 #[test]
1845 fn test_schur_ordering_new_equals_default() {
1846 let a = SchurOrdering::new();
1847 let b = SchurOrdering::default();
1848 assert_eq!(a.eliminate_rn_size, b.eliminate_rn_size);
1849 assert_eq!(a.eliminate_types.len(), b.eliminate_types.len());
1850 }
1851
1852 #[test]
1854 fn test_extract_camera_block() -> TestResult {
1855 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1856 let mut solver = SparseSchurComplementSolver::new();
1857 solver.initialize_structure(&variables, &variable_index_map)?;
1858
1859 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1861 let hessian = solver.hessian.clone().ok_or("hessian is None")?;
1862
1863 let mut fresh = SparseSchurComplementSolver::new();
1864 fresh.initialize_structure(&variables, &variable_index_map)?;
1865 let h_cc = fresh.extract_camera_block(&hessian)?;
1866
1867 assert_eq!(h_cc.nrows(), 12);
1869 assert_eq!(h_cc.ncols(), 12);
1870 Ok(())
1871 }
1872
1873 #[test]
1875 fn test_extract_coupling_block() -> TestResult {
1876 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1877 let mut solver = SparseSchurComplementSolver::new();
1878 solver.initialize_structure(&variables, &variable_index_map)?;
1879
1880 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1881 let hessian = solver.hessian.clone().ok_or("hessian is None")?;
1882
1883 let mut fresh = SparseSchurComplementSolver::new();
1884 fresh.initialize_structure(&variables, &variable_index_map)?;
1885 let h_cp = fresh.extract_coupling_block(&hessian)?;
1886
1887 assert_eq!(h_cp.nrows(), 12);
1889 assert_eq!(h_cp.ncols(), 9);
1890 Ok(())
1891 }
1892
1893 #[test]
1895 fn test_extract_landmark_blocks() -> TestResult {
1896 let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
1897 let mut solver = SparseSchurComplementSolver::new();
1898 solver.initialize_structure(&variables, &variable_index_map)?;
1899
1900 LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
1901 let hessian = solver.hessian.clone().ok_or("hessian is None")?;
1902
1903 let mut fresh = SparseSchurComplementSolver::new();
1904 fresh.initialize_structure(&variables, &variable_index_map)?;
1905 let blocks = fresh.extract_landmark_blocks(&hessian)?;
1906
1907 assert_eq!(blocks.len(), 3);
1909 Ok(())
1910 }
1911
1912 #[test]
1914 fn test_solve_with_cholesky_small_spd() -> TestResult {
1915 let solver = SparseSchurComplementSolver::new();
1916
1917 let triplets = vec![
1919 Triplet::new(0usize, 0usize, 4.0f64),
1920 Triplet::new(1usize, 0usize, 1.0f64),
1921 Triplet::new(0usize, 1usize, 1.0f64),
1922 Triplet::new(1usize, 1usize, 3.0f64),
1923 ];
1924 let a =
1925 SparseColMat::try_new_from_triplets(2, 2, &triplets).map_err(|e| format!("{e:?}"))?;
1926 let b = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); let x = solver.solve_with_cholesky(&a, &b)?;
1929 assert_eq!(x.nrows(), 2);
1930
1931 let ax0 = 4.0 * x[(0, 0)] + 1.0 * x[(1, 0)];
1934 let ax1 = 1.0 * x[(0, 0)] + 3.0 * x[(1, 0)];
1935 assert!((ax0 - 1.0).abs() < 1e-8, "A·x[0] = {ax0}");
1936 assert!((ax1 - 2.0).abs() < 1e-8, "A·x[1] = {ax1}");
1937 Ok(())
1938 }
1939
1940 #[test]
1942 fn test_solve_with_pcg_diagonal_system() -> TestResult {
1943 let solver = SparseSchurComplementSolver::new();
1944
1945 let triplets = vec![
1947 Triplet::new(0usize, 0usize, 2.0f64),
1948 Triplet::new(1usize, 1usize, 3.0f64),
1949 ];
1950 let a =
1951 SparseColMat::try_new_from_triplets(2, 2, &triplets).map_err(|e| format!("{e:?}"))?;
1952 let b = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); let x = solver.solve_with_pcg(&a, &b)?;
1955 assert!((x[(0, 0)] - 0.5).abs() < 1e-6, "x[0] = {}", x[(0, 0)]);
1957 assert!((x[(1, 0)] - 2.0 / 3.0).abs() < 1e-6, "x[1] = {}", x[(1, 0)]);
1958 Ok(())
1959 }
1960
1961 #[test]
1963 fn test_initialize_structure_no_cameras_returns_error() {
1964 use crate::core::variable::Variable;
1965 use apex_manifolds::rn;
1966 use nalgebra::DVector;
1967
1968 let mut variables: HashMap<String, VariableEnum> = HashMap::new();
1970 variables.insert(
1971 "pt_0".to_string(),
1972 VariableEnum::Rn(Variable::new(rn::Rn::from(DVector::zeros(3)))),
1973 );
1974 let mut variable_index_map: HashMap<String, usize> = HashMap::new();
1975 variable_index_map.insert("pt_0".to_string(), 0);
1976
1977 let mut solver = SparseSchurComplementSolver::new();
1978 let result = solver.initialize_structure(&variables, &variable_index_map);
1979 assert!(
1980 result.is_err(),
1981 "Expected Err when no camera variables present"
1982 );
1983 }
1984
1985 #[test]
1987 fn test_initialize_structure_no_landmarks_returns_error() {
1988 use crate::core::variable::Variable;
1989 use apex_manifolds::se3;
1990 use nalgebra::DVector;
1991
1992 let mut variables: HashMap<String, VariableEnum> = HashMap::new();
1994 variables.insert(
1995 "cam_0".to_string(),
1996 VariableEnum::SE3(Variable::new(se3::SE3::from(DVector::from_vec(vec![
1997 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
1998 ])))),
1999 );
2000 let mut variable_index_map: HashMap<String, usize> = HashMap::new();
2001 variable_index_map.insert("cam_0".to_string(), 0);
2002
2003 let mut solver = SparseSchurComplementSolver::new();
2004 let result = solver.initialize_structure(&variables, &variable_index_map);
2005 assert!(
2006 result.is_err(),
2007 "Expected Err when no landmark variables present"
2008 );
2009 }
2010}