Skip to main content

apex_solver/linalg/
explicit_schur.rs

1//! # Explicit Schur Complement Solver
2//!
3//! This module implements the **Explicit Schur Complement** method for bundle adjustment
4//! and structured optimization problems.
5//!
6//! ## Explicit vs Implicit Schur Complement
7//!
8//! **Explicit Schur:** This formulation physically constructs the reduced camera matrix
9//! (S = B - E C⁻¹ Eᵀ) in memory and solves it using direct sparse Cholesky factorization.
10//! It provides the most accurate results with moderate memory usage.
11//!
12//! **Implicit Schur:** The alternative formulation (see [`implicit_schur`](super::implicit_schur))
13//! never constructs S explicitly, instead solving the system using matrix-free PCG.
14//! It's more memory-efficient for very large problems.
15//!
16//! ## When to Use Explicit Schur
17//!
18//! - Medium-to-large bundle adjustment problems (< 10,000 cameras)
19//! - When accuracy is paramount
20//! - When you have sufficient memory to store the reduced camera system
21//! - When direct factorization is faster than iterative methods
22//!
23//! ## Usage Example
24//!
25//! ```no_run
26//! # use apex_solver::linalg::{SchurSolverAdapter, SchurVariant, SchurPreconditioner};
27//! # use std::collections::HashMap;
28//! # fn example() -> Result<(), Box<dyn std::error::Error>> {
29//! # let variables = HashMap::new();
30//! # let variable_index_map = HashMap::new();
31//! use apex_solver::linalg::{SchurSolverAdapter, SchurVariant};
32//!
33//! let mut solver = SchurSolverAdapter::new_with_structure_and_config(
34//!     &variables,
35//!     &variable_index_map,
36//!     SchurVariant::Sparse, // Explicit Schur with Cholesky
37//!     SchurPreconditioner::None,
38//! )?;
39//! # Ok(())
40//! # }
41//! ```
42
43use crate::core::problem::VariableEnum;
44use crate::linalg::{
45    LinAlgError, LinAlgResult, StructuredSparseLinearSolver, implicit_schur::IterativeSchurSolver,
46};
47use apex_manifolds::ManifoldType;
48use faer::sparse::{SparseColMat, Triplet};
49use faer::{
50    Mat, Side,
51    linalg::solvers::Solve,
52    sparse::linalg::solvers::{Llt, SymbolicLlt},
53};
54use nalgebra::Matrix3;
55use std::collections::HashMap;
56use tracing::{debug, info};
57
58/// Schur complement solver variant
59#[derive(Debug, Clone, Copy, PartialEq, Eq, Default)]
60pub enum SchurVariant {
61    /// Standard: Direct sparse Cholesky factorization of S
62    #[default]
63    Sparse,
64    /// Iterative: Conjugate Gradients on reduced system
65    Iterative,
66}
67
68/// Preconditioner type for iterative solvers
69#[derive(Debug, Clone, Copy, PartialEq, Eq, Default)]
70pub enum SchurPreconditioner {
71    /// No preconditioning
72    None,
73    /// Block diagonal of H_cc only (fast but less effective)
74    BlockDiagonal,
75    /// True Schur-Jacobi: Block diagonal of S = H_cc - H_cp * H_pp^{-1} * H_cp^T
76    /// This is what Ceres uses and provides much better PCG convergence
77    #[default]
78    SchurJacobi,
79}
80
81/// Configuration for Schur complement variable ordering
82#[derive(Debug, Clone)]
83pub struct SchurOrdering {
84    pub eliminate_types: Vec<ManifoldType>,
85    /// Only eliminate RN variables with this exact size (default: 3 for 3D landmarks)
86    /// This prevents intrinsic variables (6 DOF) from being eliminated
87    pub eliminate_rn_size: Option<usize>,
88}
89
90impl Default for SchurOrdering {
91    fn default() -> Self {
92        Self {
93            eliminate_types: vec![ManifoldType::RN],
94            eliminate_rn_size: Some(3), // Only eliminate 3D landmarks, not intrinsics
95        }
96    }
97}
98
99impl SchurOrdering {
100    pub fn new() -> Self {
101        Self::default()
102    }
103
104    /// Check if a variable should be eliminated (treated as landmark).
105    ///
106    /// Uses variable name pattern matching for robust classification:
107    /// - Variables starting with "pt_" are landmarks (must be RN with 3 DOF)
108    /// - All other variables are camera parameters (poses, intrinsics)
109    ///
110    /// This correctly handles shared intrinsics (single RN variable for all cameras)
111    /// without misclassifying them as landmarks.
112    pub fn should_eliminate(&self, name: &str, manifold_type: &ManifoldType, size: usize) -> bool {
113        // Use explicit name pattern matching
114        if name.starts_with("pt_") {
115            // This is a landmark - verify constraints
116            if !self.eliminate_types.contains(manifold_type) {
117                // Invalid manifold type for landmark - return false instead of panicking
118                return false;
119            }
120
121            // Check size constraint if specified
122            if self
123                .eliminate_rn_size
124                .is_some_and(|required_size| size != required_size)
125            {
126                // Size mismatch - return false instead of panicking
127                return false;
128            }
129            true
130        } else {
131            // Camera parameter (pose, intrinsic, etc.) - keep in camera block
132            false
133        }
134    }
135}
136
137/// Block structure for Schur complement solver
138#[derive(Debug, Clone)]
139pub struct SchurBlockStructure {
140    pub camera_blocks: Vec<(String, usize, usize)>,
141    pub landmark_blocks: Vec<(String, usize, usize)>,
142    pub camera_dof: usize,
143    pub landmark_dof: usize,
144    pub num_landmarks: usize,
145}
146
147impl SchurBlockStructure {
148    pub fn new() -> Self {
149        Self {
150            camera_blocks: Vec::new(),
151            landmark_blocks: Vec::new(),
152            camera_dof: 0,
153            landmark_dof: 0,
154            num_landmarks: 0,
155        }
156    }
157
158    pub fn camera_col_range(&self) -> (usize, usize) {
159        if self.camera_blocks.is_empty() {
160            (0, 0)
161        } else {
162            // Safe: we just checked is_empty() is false
163            let start = self.camera_blocks.first().map(|b| b.1).unwrap_or(0);
164            (start, start + self.camera_dof)
165        }
166    }
167
168    pub fn landmark_col_range(&self) -> (usize, usize) {
169        if self.landmark_blocks.is_empty() {
170            (0, 0)
171        } else {
172            // Safe: we just checked is_empty() is false
173            let start = self.landmark_blocks.first().map(|b| b.1).unwrap_or(0);
174            (start, start + self.landmark_dof)
175        }
176    }
177}
178
179impl Default for SchurBlockStructure {
180    fn default() -> Self {
181        Self::new()
182    }
183}
184
185/// Sparse Schur Complement Solver for Bundle Adjustment
186#[derive(Debug, Clone)]
187pub struct SparseSchurComplementSolver {
188    block_structure: Option<SchurBlockStructure>,
189    ordering: SchurOrdering,
190    variant: SchurVariant,
191    preconditioner: SchurPreconditioner,
192
193    // CG parameters
194    cg_max_iterations: usize,
195    cg_tolerance: f64,
196
197    // Cached matrices
198    hessian: Option<SparseColMat<usize, f64>>,
199    gradient: Option<Mat<f64>>,
200
201    // Delegate solver for iterative variant
202    iterative_solver: Option<IterativeSchurSolver>,
203}
204
205impl SparseSchurComplementSolver {
206    pub fn new() -> Self {
207        Self {
208            block_structure: None,
209            ordering: SchurOrdering::default(),
210            variant: SchurVariant::default(),
211            preconditioner: SchurPreconditioner::default(),
212            cg_max_iterations: 200, // Match Ceres (was 500)
213            cg_tolerance: 1e-6,     // Relaxed for speed (was 1e-9)
214            hessian: None,
215            gradient: None,
216            iterative_solver: None,
217        }
218    }
219
220    pub fn with_ordering(mut self, ordering: SchurOrdering) -> Self {
221        self.ordering = ordering;
222        self
223    }
224
225    pub fn with_variant(mut self, variant: SchurVariant) -> Self {
226        self.variant = variant;
227        self
228    }
229
230    pub fn with_preconditioner(mut self, preconditioner: SchurPreconditioner) -> Self {
231        self.preconditioner = preconditioner;
232        self
233    }
234
235    pub fn with_cg_params(mut self, max_iter: usize, tol: f64) -> Self {
236        self.cg_max_iterations = max_iter;
237        self.cg_tolerance = tol;
238        self
239    }
240
241    pub fn block_structure(&self) -> Option<&SchurBlockStructure> {
242        self.block_structure.as_ref()
243    }
244
245    fn build_block_structure(
246        &mut self,
247        variables: &HashMap<String, VariableEnum>,
248        variable_index_map: &HashMap<String, usize>,
249    ) -> LinAlgResult<()> {
250        let mut structure = SchurBlockStructure::new();
251
252        for (name, variable) in variables {
253            let start_col = *variable_index_map.get(name).ok_or_else(|| {
254                LinAlgError::InvalidInput(format!("Variable {} not found in index map", name))
255            })?;
256            let size = variable.get_size();
257            let manifold_type = match variable {
258                VariableEnum::SE3(_) => ManifoldType::SE3,
259                VariableEnum::SE2(_) => ManifoldType::SE2,
260                VariableEnum::SO3(_) => ManifoldType::SO3,
261                VariableEnum::SO2(_) => ManifoldType::SO2,
262                VariableEnum::Rn(_) => ManifoldType::RN,
263            };
264
265            // Use name-based classification via SchurOrdering
266            if self.ordering.should_eliminate(name, &manifold_type, size) {
267                // Landmark - to be eliminated
268                structure
269                    .landmark_blocks
270                    .push((name.clone(), start_col, size));
271                structure.landmark_dof += size;
272                structure.num_landmarks += 1;
273            } else {
274                // Camera parameter - kept in reduced system
275                structure
276                    .camera_blocks
277                    .push((name.clone(), start_col, size));
278                structure.camera_dof += size;
279            }
280        }
281
282        structure.camera_blocks.sort_by_key(|(_, col, _)| *col);
283        structure.landmark_blocks.sort_by_key(|(_, col, _)| *col);
284
285        if structure.camera_blocks.is_empty() {
286            return Err(LinAlgError::InvalidInput(
287                "No camera variables found".to_string(),
288            ));
289        }
290        if structure.landmark_blocks.is_empty() {
291            return Err(LinAlgError::InvalidInput(
292                "No landmark variables found".to_string(),
293            ));
294        }
295
296        // Log block structure for diagnostics
297        info!("Schur complement block structure:");
298        info!(
299            "  Camera blocks: {} variables, {} total DOF",
300            structure.camera_blocks.len(),
301            structure.camera_dof
302        );
303        info!(
304            "  Landmark blocks: {} variables, {} total DOF",
305            structure.landmark_blocks.len(),
306            structure.landmark_dof
307        );
308        debug!("  Camera column range: {:?}", structure.camera_col_range());
309        debug!(
310            "  Landmark column range: {:?}",
311            structure.landmark_col_range()
312        );
313        info!(
314            "  Schur complement S size: {} × {}",
315            structure.camera_dof, structure.camera_dof
316        );
317
318        // Validate column ranges are contiguous
319        let (_cam_start, cam_end) = structure.camera_col_range();
320        let (land_start, _land_end) = structure.landmark_col_range();
321        if cam_end != land_start {
322            debug!(
323                "WARNING: Gap between camera and landmark blocks! cam_end={}, land_start={}",
324                cam_end, land_start
325            );
326        }
327
328        self.block_structure = Some(structure);
329        Ok(())
330    }
331
332    /// Extract 3×3 diagonal blocks from H_pp
333    fn extract_landmark_blocks(
334        &self,
335        hessian: &SparseColMat<usize, f64>,
336    ) -> LinAlgResult<Vec<Matrix3<f64>>> {
337        let structure = self
338            .block_structure
339            .as_ref()
340            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
341
342        let mut blocks = Vec::with_capacity(structure.num_landmarks);
343        let symbolic = hessian.symbolic();
344
345        for (_, start_col, _) in &structure.landmark_blocks {
346            let mut block = Matrix3::<f64>::zeros();
347
348            for local_col in 0..3 {
349                let global_col = start_col + local_col;
350                let row_indices = symbolic.row_idx_of_col_raw(global_col);
351                let col_values = hessian.val_of_col(global_col);
352
353                for (idx, &row) in row_indices.iter().enumerate() {
354                    if row >= *start_col && row < start_col + 3 {
355                        let local_row = row - start_col;
356                        block[(local_row, local_col)] = col_values[idx];
357                    }
358                }
359            }
360
361            blocks.push(block);
362        }
363
364        Ok(blocks)
365    }
366
367    /// Invert all 3×3 blocks with numerical robustness
368    ///
369    /// This function checks the condition number of each block and applies
370    /// additional regularization for ill-conditioned blocks to prevent
371    /// numerical instability in the Schur complement computation.
372    fn invert_landmark_blocks(blocks: &[Matrix3<f64>]) -> LinAlgResult<Vec<Matrix3<f64>>> {
373        Self::invert_landmark_blocks_with_lambda(blocks, 0.0)
374    }
375
376    /// Invert all 3×3 blocks with numerical robustness and optional damping
377    ///
378    /// # Arguments
379    /// * `blocks` - The 3×3 H_pp diagonal blocks to invert
380    /// * `lambda` - LM damping parameter (already added to blocks if > 0)
381    ///
382    /// For severely ill-conditioned blocks, additional regularization is applied
383    /// to ensure numerical stability.
384    fn invert_landmark_blocks_with_lambda(
385        blocks: &[Matrix3<f64>],
386        lambda: f64,
387    ) -> LinAlgResult<Vec<Matrix3<f64>>> {
388        // Thresholds for numerical robustness
389        const CONDITION_THRESHOLD: f64 = 1e10; // Max acceptable condition number
390        const MIN_EIGENVALUE_THRESHOLD: f64 = 1e-12; // Below this is considered singular
391        const REGULARIZATION_SCALE: f64 = 1e-6; // Scale for additional regularization
392
393        let mut ill_conditioned_count = 0;
394        let mut regularized_count = 0;
395
396        let result: LinAlgResult<Vec<Matrix3<f64>>> = blocks
397            .iter()
398            .enumerate()
399            .map(|(i, block)| {
400                // Compute symmetric eigenvalues for condition number check
401                // For a 3x3 SPD matrix, eigenvalues give us the condition number
402                let eigenvalues = block.symmetric_eigenvalues();
403                let min_ev = eigenvalues.min();
404                let max_ev = eigenvalues.max();
405
406                if min_ev < MIN_EIGENVALUE_THRESHOLD {
407                    // Severely ill-conditioned: add strong regularization
408                    regularized_count += 1;
409                    let reg = lambda.max(REGULARIZATION_SCALE) + max_ev * REGULARIZATION_SCALE;
410                    let regularized = block + Matrix3::identity() * reg;
411                    regularized.try_inverse().ok_or_else(|| {
412                        LinAlgError::SingularMatrix(format!(
413                            "Landmark block {} singular even with regularization (min_ev={:.2e})",
414                            i, min_ev
415                        ))
416                    })
417                } else if max_ev / min_ev > CONDITION_THRESHOLD {
418                    // Ill-conditioned but not singular: add moderate regularization
419                    ill_conditioned_count += 1;
420                    let extra_reg = max_ev * REGULARIZATION_SCALE;
421                    let regularized = block + Matrix3::identity() * extra_reg;
422                    regularized.try_inverse().ok_or_else(|| {
423                        LinAlgError::SingularMatrix(format!(
424                            "Landmark block {} ill-conditioned (cond={:.2e})",
425                            i,
426                            max_ev / min_ev
427                        ))
428                    })
429                } else {
430                    // Well-conditioned: standard inversion
431                    block.try_inverse().ok_or_else(|| {
432                        LinAlgError::SingularMatrix(format!("Landmark block {} is singular", i))
433                    })
434                }
435            })
436            .collect();
437
438        // Log statistics about conditioning
439        if ill_conditioned_count > 0 || regularized_count > 0 {
440            debug!(
441                "Landmark block conditioning: {} ill-conditioned, {} regularized out of {}",
442                ill_conditioned_count,
443                regularized_count,
444                blocks.len()
445            );
446        }
447
448        result
449    }
450
451    /// Extract H_cc (camera-camera block)
452    fn extract_camera_block(
453        &self,
454        hessian: &SparseColMat<usize, f64>,
455    ) -> LinAlgResult<SparseColMat<usize, f64>> {
456        let structure = self
457            .block_structure
458            .as_ref()
459            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
460
461        let (cam_start, cam_end) = structure.camera_col_range();
462        let cam_size = structure.camera_dof;
463        let symbolic = hessian.symbolic();
464
465        let mut triplets = Vec::new();
466
467        for global_col in cam_start..cam_end {
468            let local_col = global_col - cam_start;
469            let row_indices = symbolic.row_idx_of_col_raw(global_col);
470            let col_values = hessian.val_of_col(global_col);
471
472            for (idx, &global_row) in row_indices.iter().enumerate() {
473                if global_row >= cam_start && global_row < cam_end {
474                    let local_row = global_row - cam_start;
475                    triplets.push(Triplet::new(local_row, local_col, col_values[idx]));
476                }
477            }
478        }
479
480        SparseColMat::try_new_from_triplets(cam_size, cam_size, &triplets)
481            .map_err(|e| LinAlgError::SparseMatrixCreation(format!("H_cc: {:?}", e)))
482    }
483
484    /// Extract H_cp (camera-point coupling)
485    fn extract_coupling_block(
486        &self,
487        hessian: &SparseColMat<usize, f64>,
488    ) -> LinAlgResult<SparseColMat<usize, f64>> {
489        let structure = self
490            .block_structure
491            .as_ref()
492            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
493
494        let (cam_start, cam_end) = structure.camera_col_range();
495        let (land_start, land_end) = structure.landmark_col_range();
496        let cam_size = structure.camera_dof;
497        let land_size = structure.landmark_dof;
498        let symbolic = hessian.symbolic();
499
500        let mut triplets = Vec::new();
501
502        for global_col in land_start..land_end {
503            let local_col = global_col - land_start;
504            let row_indices = symbolic.row_idx_of_col_raw(global_col);
505            let col_values = hessian.val_of_col(global_col);
506
507            for (idx, &global_row) in row_indices.iter().enumerate() {
508                if global_row >= cam_start && global_row < cam_end {
509                    let local_row = global_row - cam_start;
510                    triplets.push(Triplet::new(local_row, local_col, col_values[idx]));
511                }
512            }
513        }
514
515        SparseColMat::try_new_from_triplets(cam_size, land_size, &triplets)
516            .map_err(|e| LinAlgError::SparseMatrixCreation(format!("H_cp: {:?}", e)))
517    }
518
519    /// Extract gradient blocks
520    fn extract_gradient_blocks(&self, gradient: &Mat<f64>) -> LinAlgResult<(Mat<f64>, Mat<f64>)> {
521        let structure = self
522            .block_structure
523            .as_ref()
524            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
525
526        let (cam_start, cam_end) = structure.camera_col_range();
527        let (land_start, land_end) = structure.landmark_col_range();
528
529        let mut g_c = Mat::zeros(structure.camera_dof, 1);
530        for i in 0..(cam_end - cam_start) {
531            g_c[(i, 0)] = gradient[(cam_start + i, 0)];
532        }
533
534        let mut g_p = Mat::zeros(structure.landmark_dof, 1);
535        for i in 0..(land_end - land_start) {
536            g_p[(i, 0)] = gradient[(land_start + i, 0)];
537        }
538
539        Ok((g_c, g_p))
540    }
541
542    /// Solve S * x = b using Cholesky factorization with automatic regularization
543    ///
544    /// If the initial factorization fails (matrix not positive definite),
545    /// we add small regularization to the diagonal and retry.
546    fn solve_with_cholesky(
547        &self,
548        a: &SparseColMat<usize, f64>,
549        b: &Mat<f64>,
550    ) -> LinAlgResult<Mat<f64>> {
551        let sym = SymbolicLlt::try_new(a.symbolic(), Side::Lower).map_err(|e| {
552            LinAlgError::FactorizationFailed(format!("Symbolic Cholesky failed: {:?}", e))
553        })?;
554
555        // First attempt: direct factorization
556        match Llt::try_new_with_symbolic(sym.clone(), a.as_ref(), Side::Lower) {
557            Ok(cholesky) => return Ok(cholesky.solve(b)),
558            Err(e) => {
559                debug!(
560                    "Cholesky factorization failed: {:?}. Applying regularization.",
561                    e
562                );
563            }
564        }
565
566        // Retry with exponentially increasing regularization
567        let n = a.nrows();
568        let symbolic = a.symbolic();
569
570        // Compute trace and max diagonal for scaling
571        let mut trace = 0.0;
572        let mut max_diag = 0.0f64;
573        for col in 0..n {
574            let row_indices = symbolic.row_idx_of_col_raw(col);
575            let col_values = a.val_of_col(col);
576            for (idx, &row) in row_indices.iter().enumerate() {
577                if row == col {
578                    trace += col_values[idx];
579                    max_diag = max_diag.max(col_values[idx].abs());
580                }
581            }
582        }
583
584        // Try multiple regularization levels
585        let avg_diag = trace / n as f64;
586        let base_reg = avg_diag.max(max_diag).max(1.0);
587
588        for attempt in 0..5 {
589            let reg = base_reg * 10.0f64.powi(attempt - 4); // 1e-4, 1e-3, 1e-2, 1e-1, 1.0 times base
590            debug!(
591                "Cholesky attempt {}: regularization = {:.2e}",
592                attempt + 2,
593                reg
594            );
595
596            let mut triplets = Vec::with_capacity(n * 10);
597            for col in 0..n {
598                let row_indices = symbolic.row_idx_of_col_raw(col);
599                let col_values = a.val_of_col(col);
600                for (idx, &row) in row_indices.iter().enumerate() {
601                    triplets.push(Triplet::new(row, col, col_values[idx]));
602                }
603            }
604
605            for i in 0..n {
606                triplets.push(Triplet::new(i, i, reg));
607            }
608
609            let a_reg = match SparseColMat::try_new_from_triplets(n, n, &triplets) {
610                Ok(m) => m,
611                Err(e) => {
612                    debug!("Failed to create regularized matrix: {:?}", e);
613                    continue;
614                }
615            };
616
617            // Need to create a new symbolic structure for the regularized matrix
618            let sym_reg = match SymbolicLlt::try_new(a_reg.symbolic(), Side::Lower) {
619                Ok(s) => s,
620                Err(e) => {
621                    debug!("Symbolic factorization failed: {:?}", e);
622                    continue;
623                }
624            };
625
626            match Llt::try_new_with_symbolic(sym_reg, a_reg.as_ref(), Side::Lower) {
627                Ok(cholesky) => {
628                    debug!("Cholesky succeeded with regularization {:.2e}", reg);
629                    return Ok(cholesky.solve(b));
630                }
631                Err(e) => {
632                    debug!("Cholesky failed with reg {:.2e}: {:?}", reg, e);
633                }
634            }
635        }
636
637        Err(LinAlgError::SingularMatrix(format!(
638            "Schur complement singular after 5 regularization attempts (max reg = {:.2e})",
639            base_reg
640        )))
641    }
642
643    /// Solve using Preconditioned Conjugate Gradients (PCG)
644    ///
645    /// Uses Jacobi (diagonal) preconditioning for simplicity and robustness.
646    fn solve_with_pcg(&self, a: &SparseColMat<usize, f64>, b: &Mat<f64>) -> LinAlgResult<Mat<f64>> {
647        let n = b.nrows();
648        let max_iterations = self.cg_max_iterations;
649        let tolerance = self.cg_tolerance;
650
651        // Extract diagonal for Jacobi preconditioner
652        let symbolic = a.symbolic();
653        let mut precond = vec![1.0; n];
654        for (col, precond_val) in precond.iter_mut().enumerate().take(n) {
655            let row_indices = symbolic.row_idx_of_col_raw(col);
656            let col_values = a.val_of_col(col);
657            for (idx, &row) in row_indices.iter().enumerate() {
658                if row == col {
659                    let diag = col_values[idx];
660                    *precond_val = if diag.abs() > 1e-12 { 1.0 / diag } else { 1.0 };
661                    break;
662                }
663            }
664        }
665
666        // Initialize
667        let mut x = Mat::<f64>::zeros(n, 1);
668
669        // r = b - A*x (x starts at 0, so r = b)
670        let mut r = b.clone();
671
672        // z = M^{-1} * r (Jacobi preconditioning)
673        let mut z = Mat::<f64>::zeros(n, 1);
674        for i in 0..n {
675            z[(i, 0)] = precond[i] * r[(i, 0)];
676        }
677
678        let mut p = z.clone();
679
680        let mut rz_old = 0.0;
681        for i in 0..n {
682            rz_old += r[(i, 0)] * z[(i, 0)];
683        }
684
685        // Compute initial residual norm for relative tolerance
686        let mut r_norm_init = 0.0;
687        for i in 0..n {
688            r_norm_init += r[(i, 0)] * r[(i, 0)];
689        }
690        r_norm_init = r_norm_init.sqrt();
691        let abs_tol = tolerance * r_norm_init.max(1.0);
692
693        for _iter in 0..max_iterations {
694            // Ap = A * p (sparse matrix-vector product)
695            let mut ap = Mat::<f64>::zeros(n, 1);
696            for col in 0..n {
697                let row_indices = symbolic.row_idx_of_col_raw(col);
698                let col_values = a.val_of_col(col);
699                for (idx, &row) in row_indices.iter().enumerate() {
700                    ap[(row, 0)] += col_values[idx] * p[(col, 0)];
701                }
702            }
703
704            // alpha = (r^T z) / (p^T Ap)
705            let mut p_ap = 0.0;
706            for i in 0..n {
707                p_ap += p[(i, 0)] * ap[(i, 0)];
708            }
709
710            if p_ap.abs() < 1e-30 {
711                break;
712            }
713
714            let alpha = rz_old / p_ap;
715
716            // x = x + alpha * p
717            for i in 0..n {
718                x[(i, 0)] += alpha * p[(i, 0)];
719            }
720
721            // r = r - alpha * Ap
722            for i in 0..n {
723                r[(i, 0)] -= alpha * ap[(i, 0)];
724            }
725
726            // Check convergence
727            let mut r_norm = 0.0;
728            for i in 0..n {
729                r_norm += r[(i, 0)] * r[(i, 0)];
730            }
731            r_norm = r_norm.sqrt();
732
733            if r_norm < abs_tol {
734                break;
735            }
736
737            // z = M^{-1} * r
738            for i in 0..n {
739                z[(i, 0)] = precond[i] * r[(i, 0)];
740            }
741
742            // beta = (r_{k+1}^T z_{k+1}) / (r_k^T z_k)
743            let mut rz_new = 0.0;
744            for i in 0..n {
745                rz_new += r[(i, 0)] * z[(i, 0)];
746            }
747
748            if rz_old.abs() < 1e-30 {
749                break;
750            }
751
752            let beta = rz_new / rz_old;
753
754            // p = z + beta * p
755            for i in 0..n {
756                p[(i, 0)] = z[(i, 0)] + beta * p[(i, 0)];
757            }
758
759            rz_old = rz_new;
760        }
761
762        Ok(x)
763    }
764
765    /// Compute Schur complement: S = H_cc - H_cp * H_pp^{-1} * H_cp^T
766    ///
767    /// This is an efficient implementation that exploits:
768    /// 1. Block-diagonal structure of H_pp (each landmark is independent)
769    /// 2. Sparsity of H_cp (each landmark connects to only a few cameras)
770    /// 3. Dense accumulation for the small camera-camera matrix S
771    ///
772    /// Algorithm:
773    /// For each landmark block p:
774    ///   - Get the cameras that observe this landmark (non-zero rows in H_cp column block)
775    ///   - Compute contribution: H_cp[:, p] * H_pp[p,p]^{-1} * H_cp[:, p]^T
776    ///   - This is an outer product of sparse vectors, producing a small dense update
777    ///   - Accumulate into the dense result S
778    fn compute_schur_complement(
779        &self,
780        h_cc: &SparseColMat<usize, f64>,
781        h_cp: &SparseColMat<usize, f64>,
782        hpp_inv_blocks: &[Matrix3<f64>],
783    ) -> LinAlgResult<SparseColMat<usize, f64>> {
784        let cam_size = h_cc.nrows();
785        let h_cp_symbolic = h_cp.symbolic();
786
787        // Use a dense matrix for S since the Schur complement is typically dense
788        // For 89 cameras, this is only 89*89*8 = 63KB - very cache-friendly
789        let mut s_dense = vec![0.0f64; cam_size * cam_size];
790
791        // First, add H_cc to S
792        let h_cc_symbolic = h_cc.symbolic();
793        for col in 0..h_cc.ncols() {
794            let row_indices = h_cc_symbolic.row_idx_of_col_raw(col);
795            let col_values = h_cc.val_of_col(col);
796            for (idx, &row) in row_indices.iter().enumerate() {
797                s_dense[row * cam_size + col] += col_values[idx];
798            }
799        }
800
801        // Pre-allocate vectors for camera data per landmark
802        // Max cameras per landmark is bounded by number of cameras
803        let mut cam_rows: Vec<usize> = Vec::with_capacity(32);
804        let mut h_cp_block: Vec<[f64; 3]> = Vec::with_capacity(32);
805        let mut contrib_block: Vec<[f64; 3]> = Vec::with_capacity(32);
806
807        // Process each landmark block independently (sequential for efficiency)
808        for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
809            let col_start = block_idx * 3;
810
811            cam_rows.clear();
812            h_cp_block.clear();
813
814            if col_start + 2 >= h_cp.ncols() {
815                continue;
816            }
817
818            let row_indices_0 = h_cp_symbolic.row_idx_of_col_raw(col_start);
819            let col_values_0 = h_cp.val_of_col(col_start);
820            let row_indices_1 = h_cp_symbolic.row_idx_of_col_raw(col_start + 1);
821            let col_values_1 = h_cp.val_of_col(col_start + 1);
822            let row_indices_2 = h_cp_symbolic.row_idx_of_col_raw(col_start + 2);
823            let col_values_2 = h_cp.val_of_col(col_start + 2);
824
825            let mut i0 = 0;
826            let mut i1 = 0;
827            let mut i2 = 0;
828
829            while i0 < row_indices_0.len() || i1 < row_indices_1.len() || i2 < row_indices_2.len() {
830                let r0 = if i0 < row_indices_0.len() {
831                    row_indices_0[i0]
832                } else {
833                    usize::MAX
834                };
835                let r1 = if i1 < row_indices_1.len() {
836                    row_indices_1[i1]
837                } else {
838                    usize::MAX
839                };
840                let r2 = if i2 < row_indices_2.len() {
841                    row_indices_2[i2]
842                } else {
843                    usize::MAX
844                };
845
846                let min_row = r0.min(r1).min(r2);
847                if min_row == usize::MAX {
848                    break;
849                }
850
851                let v0 = if r0 == min_row {
852                    i0 += 1;
853                    col_values_0[i0 - 1]
854                } else {
855                    0.0
856                };
857                let v1 = if r1 == min_row {
858                    i1 += 1;
859                    col_values_1[i1 - 1]
860                } else {
861                    0.0
862                };
863                let v2 = if r2 == min_row {
864                    i2 += 1;
865                    col_values_2[i2 - 1]
866                } else {
867                    0.0
868                };
869
870                cam_rows.push(min_row);
871                h_cp_block.push([v0, v1, v2]);
872            }
873
874            if cam_rows.is_empty() {
875                continue;
876            }
877
878            contrib_block.clear();
879            for h_cp_row in &h_cp_block {
880                let c0 = h_cp_row[0] * hpp_inv_block[(0, 0)]
881                    + h_cp_row[1] * hpp_inv_block[(1, 0)]
882                    + h_cp_row[2] * hpp_inv_block[(2, 0)];
883                let c1 = h_cp_row[0] * hpp_inv_block[(0, 1)]
884                    + h_cp_row[1] * hpp_inv_block[(1, 1)]
885                    + h_cp_row[2] * hpp_inv_block[(2, 1)];
886                let c2 = h_cp_row[0] * hpp_inv_block[(0, 2)]
887                    + h_cp_row[1] * hpp_inv_block[(1, 2)]
888                    + h_cp_row[2] * hpp_inv_block[(2, 2)];
889                contrib_block.push([c0, c1, c2]);
890            }
891
892            let n_cams = cam_rows.len();
893            for i in 0..n_cams {
894                let cam_i = cam_rows[i];
895                let contrib_i = &contrib_block[i];
896                for j in 0..n_cams {
897                    let cam_j = cam_rows[j];
898                    let h_cp_j = &h_cp_block[j];
899                    let dot = contrib_i[0] * h_cp_j[0]
900                        + contrib_i[1] * h_cp_j[1]
901                        + contrib_i[2] * h_cp_j[2];
902                    s_dense[cam_i * cam_size + cam_j] -= dot;
903                }
904            }
905        }
906
907        // Symmetrize the Schur complement to ensure numerical symmetry
908        // Due to floating-point accumulation errors across 156K+ landmarks,
909        // S can become slightly asymmetric. Force symmetry: S = 0.5 * (S + S^T)
910        for i in 0..cam_size {
911            for j in (i + 1)..cam_size {
912                let avg = (s_dense[i * cam_size + j] + s_dense[j * cam_size + i]) * 0.5;
913                s_dense[i * cam_size + j] = avg;
914                s_dense[j * cam_size + i] = avg;
915            }
916        }
917
918        // Convert dense matrix to sparse (filtering near-zeros)
919        // Use slightly larger threshold to avoid numerical noise issues
920        let mut s_triplets: Vec<Triplet<usize, usize, f64>> = Vec::new();
921        for col in 0..cam_size {
922            for row in 0..cam_size {
923                let val = s_dense[row * cam_size + col];
924                if val.abs() > 1e-12 {
925                    s_triplets.push(Triplet::new(row, col, val));
926                }
927            }
928        }
929
930        SparseColMat::try_new_from_triplets(cam_size, cam_size, &s_triplets)
931            .map_err(|e| LinAlgError::SparseMatrixCreation(format!("Schur S: {:?}", e)))
932    }
933
934    /// Compute reduced gradient: g_reduced = g_c - H_cp * H_pp^{-1} * g_p
935    fn compute_reduced_gradient(
936        &self,
937        g_c: &Mat<f64>,
938        g_p: &Mat<f64>,
939        h_cp: &SparseColMat<usize, f64>,
940        hpp_inv_blocks: &[Matrix3<f64>],
941    ) -> LinAlgResult<Mat<f64>> {
942        // Infer sizes from matrices
943        let land_size = g_p.nrows();
944        let cam_size = g_c.nrows();
945
946        // Compute H_pp^{-1} * g_p block-wise
947        let mut hpp_inv_gp = Mat::zeros(land_size, 1);
948
949        for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
950            let row_start = block_idx * 3;
951
952            let gp_block = nalgebra::Vector3::new(
953                g_p[(row_start, 0)],
954                g_p[(row_start + 1, 0)],
955                g_p[(row_start + 2, 0)],
956            );
957
958            let result = hpp_inv_block * gp_block;
959            hpp_inv_gp[(row_start, 0)] = result[0];
960            hpp_inv_gp[(row_start + 1, 0)] = result[1];
961            hpp_inv_gp[(row_start + 2, 0)] = result[2];
962        }
963
964        // Compute H_cp * (H_pp^{-1} * g_p)
965        let mut h_cp_hpp_inv_gp = Mat::<f64>::zeros(cam_size, 1);
966        let symbolic = h_cp.symbolic();
967
968        for col in 0..h_cp.ncols() {
969            let row_indices = symbolic.row_idx_of_col_raw(col);
970            let col_values = h_cp.val_of_col(col);
971
972            for (idx, &row) in row_indices.iter().enumerate() {
973                h_cp_hpp_inv_gp[(row, 0)] += col_values[idx] * hpp_inv_gp[(col, 0)];
974            }
975        }
976
977        // g_reduced = g_c - H_cp * H_pp^{-1} * g_p
978        let mut g_reduced = Mat::zeros(cam_size, 1);
979        for i in 0..cam_size {
980            g_reduced[(i, 0)] = g_c[(i, 0)] - h_cp_hpp_inv_gp[(i, 0)];
981        }
982
983        Ok(g_reduced)
984    }
985
986    /// Back-substitute: δp = H_pp^{-1} * (g_p - H_cp^T * δc)
987    fn back_substitute(
988        &self,
989        delta_c: &Mat<f64>,
990        g_p: &Mat<f64>,
991        h_cp: &SparseColMat<usize, f64>,
992        hpp_inv_blocks: &[Matrix3<f64>],
993    ) -> LinAlgResult<Mat<f64>> {
994        // Infer size from matrix
995
996        let land_size = g_p.nrows();
997
998        // Compute H_cp^T * δc
999        let mut h_cp_t_delta_c = Mat::<f64>::zeros(land_size, 1);
1000        let symbolic = h_cp.symbolic();
1001
1002        for col in 0..h_cp.ncols() {
1003            let row_indices = symbolic.row_idx_of_col_raw(col);
1004            let col_values = h_cp.val_of_col(col);
1005
1006            for (idx, &row) in row_indices.iter().enumerate() {
1007                h_cp_t_delta_c[(col, 0)] += col_values[idx] * delta_c[(row, 0)];
1008            }
1009        }
1010
1011        // Compute rhs = g_p - H_cp^T * δc
1012        let mut rhs = Mat::zeros(land_size, 1);
1013        for i in 0..land_size {
1014            rhs[(i, 0)] = g_p[(i, 0)] - h_cp_t_delta_c[(i, 0)];
1015        }
1016
1017        // Compute δp = H_pp^{-1} * rhs block-wise
1018        let mut delta_p = Mat::zeros(land_size, 1);
1019
1020        for (block_idx, hpp_inv_block) in hpp_inv_blocks.iter().enumerate() {
1021            let row_start = block_idx * 3;
1022
1023            let rhs_block = nalgebra::Vector3::new(
1024                rhs[(row_start, 0)],
1025                rhs[(row_start + 1, 0)],
1026                rhs[(row_start + 2, 0)],
1027            );
1028
1029            let result = hpp_inv_block * rhs_block;
1030            delta_p[(row_start, 0)] = result[0];
1031            delta_p[(row_start + 1, 0)] = result[1];
1032            delta_p[(row_start + 2, 0)] = result[2];
1033        }
1034
1035        Ok(delta_p)
1036    }
1037}
1038
1039impl Default for SparseSchurComplementSolver {
1040    fn default() -> Self {
1041        Self::new()
1042    }
1043}
1044
1045impl StructuredSparseLinearSolver for SparseSchurComplementSolver {
1046    fn initialize_structure(
1047        &mut self,
1048        variables: &HashMap<String, VariableEnum>,
1049        variable_index_map: &HashMap<String, usize>,
1050    ) -> LinAlgResult<()> {
1051        // Build block structure for all variants
1052        self.build_block_structure(variables, variable_index_map)?;
1053
1054        // Initialize delegate solver based on variant
1055        match self.variant {
1056            SchurVariant::Iterative => {
1057                let mut solver =
1058                    IterativeSchurSolver::with_cg_params(self.cg_max_iterations, self.cg_tolerance);
1059                solver.initialize_structure(variables, variable_index_map)?;
1060                self.iterative_solver = Some(solver);
1061            }
1062            SchurVariant::Sparse => {
1063                // No delegate solver needed for sparse variant
1064            }
1065        }
1066
1067        Ok(())
1068    }
1069
1070    fn solve_normal_equation(
1071        &mut self,
1072        residuals: &Mat<f64>,
1073        jacobians: &SparseColMat<usize, f64>,
1074    ) -> LinAlgResult<Mat<f64>> {
1075        use std::ops::Mul;
1076
1077        if self.block_structure.is_none() {
1078            return Err(LinAlgError::InvalidInput(
1079                "Block structure not built. Call initialize_structure() first.".to_string(),
1080            ));
1081        }
1082
1083        // Sparse and Iterative variants use the same Schur complement formation
1084        // They differ only in how S*δc = g_reduced is solved:
1085        // - Sparse: Cholesky factorization
1086        // - Iterative: PCG
1087
1088        // 1. Build H = J^T * J and g = -J^T * r
1089        let jt = jacobians
1090            .transpose()
1091            .to_col_major()
1092            .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
1093        let hessian = jt.mul(jacobians);
1094        let gradient = jacobians.transpose().mul(residuals);
1095        let mut neg_gradient = Mat::zeros(gradient.nrows(), 1);
1096        for i in 0..gradient.nrows() {
1097            neg_gradient[(i, 0)] = -gradient[(i, 0)];
1098        }
1099
1100        self.hessian = Some(hessian.clone());
1101        // Store the positive gradient (J^T * r) for predicted reduction calculation
1102        // The Schur solver internally uses neg_gradient (-J^T * r) for the solve
1103        self.gradient = Some(gradient.clone());
1104
1105        // 2. Extract blocks
1106        let h_cc = self.extract_camera_block(&hessian)?;
1107        let h_cp = self.extract_coupling_block(&hessian)?;
1108        let hpp_blocks = self.extract_landmark_blocks(&hessian)?;
1109        let (g_c, g_p) = self.extract_gradient_blocks(&neg_gradient)?;
1110
1111        // 3. Invert H_pp blocks
1112        let hpp_inv_blocks = Self::invert_landmark_blocks(&hpp_blocks)?;
1113
1114        // 4. Compute Schur complement S
1115        let s = self.compute_schur_complement(&h_cc, &h_cp, &hpp_inv_blocks)?;
1116
1117        // 5. Compute reduced gradient
1118        let g_reduced = self.compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1119
1120        // 6. Solve S * δc = g_reduced (Cholesky for Sparse, PCG for Iterative)
1121        let delta_c = match self.variant {
1122            SchurVariant::Iterative => self.solve_with_pcg(&s, &g_reduced)?,
1123            _ => self.solve_with_cholesky(&s, &g_reduced)?,
1124        };
1125
1126        // 7. Back-substitute for δp
1127        let delta_p = self.back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1128
1129        // 8. Combine results
1130        self.combine_updates(&delta_c, &delta_p)
1131    }
1132
1133    fn solve_augmented_equation(
1134        &mut self,
1135        residuals: &Mat<f64>,
1136        jacobians: &SparseColMat<usize, f64>,
1137        lambda: f64,
1138    ) -> LinAlgResult<Mat<f64>> {
1139        use std::ops::Mul;
1140
1141        if self.block_structure.is_none() {
1142            return Err(LinAlgError::InvalidInput(
1143                "Block structure not built. Call initialize_structure() first.".to_string(),
1144            ));
1145        }
1146
1147        // Sparse and Iterative variants use the same Schur complement formation with damping
1148        // 1. Build H = J^T * J and g = -J^T * r
1149        let jt = jacobians
1150            .transpose()
1151            .to_col_major()
1152            .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
1153        let hessian = jt.mul(jacobians);
1154        let gradient = jacobians.transpose().mul(residuals);
1155        let mut neg_gradient = Mat::zeros(gradient.nrows(), 1);
1156        for i in 0..gradient.nrows() {
1157            neg_gradient[(i, 0)] = -gradient[(i, 0)];
1158        }
1159
1160        self.hessian = Some(hessian.clone());
1161        // Store the positive gradient (J^T * r) for predicted reduction calculation
1162        // The Schur solver internally uses neg_gradient (-J^T * r) for the solve
1163        self.gradient = Some(gradient.clone());
1164
1165        // 2. Extract blocks
1166        let h_cc = self.extract_camera_block(&hessian)?;
1167        let h_cp = self.extract_coupling_block(&hessian)?;
1168        let mut hpp_blocks = self.extract_landmark_blocks(&hessian)?;
1169        let (g_c, g_p) = self.extract_gradient_blocks(&neg_gradient)?;
1170
1171        // Log matrix dimensions for diagnostics
1172        debug!("Iteration matrices:");
1173        debug!(
1174            "  Hessian (J^T*J): {} × {}",
1175            hessian.nrows(),
1176            hessian.ncols()
1177        );
1178        debug!("  H_cc (camera): {} × {}", h_cc.nrows(), h_cc.ncols());
1179        debug!("  H_cp (coupling): {} × {}", h_cp.nrows(), h_cp.ncols());
1180        debug!("  H_pp blocks: {} (3×3 each)", hpp_blocks.len());
1181
1182        // 3. Add damping to H_cc and H_pp
1183        let structure = self
1184            .block_structure
1185            .as_ref()
1186            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
1187        let cam_size = structure.camera_dof;
1188
1189        // Add λI to H_cc
1190        let mut h_cc_triplets = Vec::new();
1191        let h_cc_symbolic = h_cc.symbolic();
1192        for col in 0..h_cc.ncols() {
1193            let row_indices = h_cc_symbolic.row_idx_of_col_raw(col);
1194            let col_values = h_cc.val_of_col(col);
1195            for (idx, &row) in row_indices.iter().enumerate() {
1196                h_cc_triplets.push(Triplet::new(row, col, col_values[idx]));
1197            }
1198        }
1199        for i in 0..cam_size {
1200            if let Some(entry) = h_cc_triplets.iter_mut().find(|t| t.row == i && t.col == i) {
1201                *entry = Triplet::new(i, i, entry.val + lambda);
1202            } else {
1203                h_cc_triplets.push(Triplet::new(i, i, lambda));
1204            }
1205        }
1206        let h_cc_damped =
1207            SparseColMat::try_new_from_triplets(cam_size, cam_size, &h_cc_triplets)
1208                .map_err(|e| LinAlgError::SparseMatrixCreation(format!("Damped H_cc: {:?}", e)))?;
1209
1210        // Add λI to H_pp blocks
1211        for block in &mut hpp_blocks {
1212            block[(0, 0)] += lambda;
1213            block[(1, 1)] += lambda;
1214            block[(2, 2)] += lambda;
1215        }
1216
1217        // 4. Invert damped H_pp blocks
1218        let hpp_inv_blocks = Self::invert_landmark_blocks(&hpp_blocks)?;
1219
1220        // 5. Compute Schur complement with damped matrices
1221        let s = self.compute_schur_complement(&h_cc_damped, &h_cp, &hpp_inv_blocks)?;
1222
1223        // 6. Compute reduced gradient
1224        let g_reduced = self.compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1225
1226        // 7. Solve S * δc = g_reduced (Cholesky for Sparse, PCG for Iterative)
1227        let delta_c = match self.variant {
1228            SchurVariant::Iterative => self.solve_with_pcg(&s, &g_reduced)?,
1229            _ => self.solve_with_cholesky(&s, &g_reduced)?,
1230        };
1231
1232        // 8. Back-substitute for δp
1233        let delta_p = self.back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv_blocks)?;
1234
1235        // 9. Combine results
1236        self.combine_updates(&delta_c, &delta_p)
1237    }
1238
1239    fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>> {
1240        self.hessian.as_ref()
1241    }
1242
1243    fn get_gradient(&self) -> Option<&Mat<f64>> {
1244        self.gradient.as_ref()
1245    }
1246}
1247
1248// Helper methods for SparseSchurComplementSolver
1249impl SparseSchurComplementSolver {
1250    /// Combine camera and landmark updates into full update vector
1251    fn combine_updates(&self, delta_c: &Mat<f64>, delta_p: &Mat<f64>) -> LinAlgResult<Mat<f64>> {
1252        let structure = self
1253            .block_structure
1254            .as_ref()
1255            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not built".to_string()))?;
1256
1257        let total_dof = structure.camera_dof + structure.landmark_dof;
1258        let mut delta = Mat::zeros(total_dof, 1);
1259
1260        let (cam_start, cam_end) = structure.camera_col_range();
1261        let (land_start, land_end) = structure.landmark_col_range();
1262
1263        // Copy camera updates
1264        for i in 0..(cam_end - cam_start) {
1265            delta[(cam_start + i, 0)] = delta_c[(i, 0)];
1266        }
1267
1268        // Copy landmark updates
1269        for i in 0..(land_end - land_start) {
1270            delta[(land_start + i, 0)] = delta_p[(i, 0)];
1271        }
1272
1273        // Debug: Log update magnitude
1274        debug!(
1275            "Update norms: delta_c={:.6e}, delta_p={:.6e}, combined={:.6e}",
1276            delta_c.norm_l2(),
1277            delta_p.norm_l2(),
1278            delta.norm_l2()
1279        );
1280
1281        Ok(delta)
1282    }
1283}
1284
1285/// Adapter to use SparseSchurComplementSolver as a standard SparseLinearSolver
1286///
1287/// This adapter bridges the gap between StructuredSparseLinearSolver (which requires
1288/// variable information) and the standard SparseLinearSolver trait used by optimizers.
1289pub struct SchurSolverAdapter {
1290    schur_solver: SparseSchurComplementSolver,
1291    initialized: bool,
1292}
1293
1294impl SchurSolverAdapter {
1295    /// Create a new Schur solver adapter with problem structure
1296    ///
1297    /// This initializes the internal Schur solver with variable partitioning information.
1298    ///
1299    /// # Arguments
1300    /// * `variables` - Map of variable names to their typed instances
1301    /// * `variable_index_map` - Map from variable names to starting column indices in Jacobian
1302    ///
1303    /// # Returns
1304    /// Initialized adapter ready to solve linear systems
1305    pub fn new_with_structure(
1306        variables: &std::collections::HashMap<String, crate::core::problem::VariableEnum>,
1307        variable_index_map: &std::collections::HashMap<String, usize>,
1308    ) -> LinAlgResult<Self> {
1309        let mut solver = SparseSchurComplementSolver::new();
1310        solver.initialize_structure(variables, variable_index_map)?;
1311        Ok(Self {
1312            schur_solver: solver,
1313            initialized: true,
1314        })
1315    }
1316
1317    /// Create with custom configuration
1318    pub fn new_with_structure_and_config(
1319        variables: &std::collections::HashMap<String, crate::core::problem::VariableEnum>,
1320        variable_index_map: &std::collections::HashMap<String, usize>,
1321        variant: SchurVariant,
1322        preconditioner: SchurPreconditioner,
1323    ) -> LinAlgResult<Self> {
1324        let mut solver = SparseSchurComplementSolver::new()
1325            .with_variant(variant)
1326            .with_preconditioner(preconditioner);
1327        solver.initialize_structure(variables, variable_index_map)?;
1328        Ok(Self {
1329            schur_solver: solver,
1330            initialized: true,
1331        })
1332    }
1333}
1334
1335impl crate::linalg::SparseLinearSolver for SchurSolverAdapter {
1336    fn solve_normal_equation(
1337        &mut self,
1338        residuals: &Mat<f64>,
1339        jacobian: &SparseColMat<usize, f64>,
1340    ) -> LinAlgResult<Mat<f64>> {
1341        if !self.initialized {
1342            return Err(LinAlgError::InvalidInput(
1343                "Schur solver adapter not initialized with structure".to_string(),
1344            ));
1345        }
1346        self.schur_solver.solve_normal_equation(residuals, jacobian)
1347    }
1348
1349    fn solve_augmented_equation(
1350        &mut self,
1351        residuals: &Mat<f64>,
1352        jacobian: &SparseColMat<usize, f64>,
1353        lambda: f64,
1354    ) -> LinAlgResult<Mat<f64>> {
1355        if !self.initialized {
1356            return Err(LinAlgError::InvalidInput(
1357                "Schur solver adapter not initialized with structure".to_string(),
1358            ));
1359        }
1360        self.schur_solver
1361            .solve_augmented_equation(residuals, jacobian, lambda)
1362    }
1363
1364    fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>> {
1365        self.schur_solver.get_hessian()
1366    }
1367
1368    fn get_gradient(&self) -> Option<&Mat<f64>> {
1369        self.schur_solver.get_gradient()
1370    }
1371
1372    fn compute_covariance_matrix(&mut self) -> Option<&Mat<f64>> {
1373        // TODO: Implement covariance computation for Schur complement solver
1374        // This requires inverting the Schur complement S, which is non-trivial
1375        // For now, return None
1376        None
1377    }
1378
1379    fn get_covariance_matrix(&self) -> Option<&Mat<f64>> {
1380        // Not implemented yet
1381        None
1382    }
1383}
1384
1385#[cfg(test)]
1386#[allow(clippy::unwrap_used, clippy::expect_used)]
1387mod tests {
1388    use super::*;
1389
1390    #[test]
1391    fn test_schur_ordering_shared_intrinsics() {
1392        let ordering = SchurOrdering::default();
1393
1394        // Landmarks should be eliminated
1395        assert!(ordering.should_eliminate("pt_00000", &ManifoldType::RN, 3));
1396        assert!(ordering.should_eliminate("pt_12345", &ManifoldType::RN, 3));
1397
1398        // Camera poses should NOT be eliminated
1399        assert!(!ordering.should_eliminate("cam_0000", &ManifoldType::SE3, 6));
1400        assert!(!ordering.should_eliminate("cam_0042", &ManifoldType::SE3, 6));
1401
1402        // Shared intrinsics (RN, 3 DOF) should NOT be eliminated - KEY TEST!
1403        assert!(!ordering.should_eliminate("shared_intrinsics", &ManifoldType::RN, 3));
1404
1405        // Per-camera intrinsics should NOT be eliminated
1406        assert!(!ordering.should_eliminate("intr_0000", &ManifoldType::RN, 3));
1407        assert!(!ordering.should_eliminate("intr_0042", &ManifoldType::RN, 3));
1408    }
1409
1410    #[test]
1411    fn test_schur_ordering_multiple_intrinsic_groups() {
1412        let ordering = SchurOrdering::default();
1413
1414        // Test that multiple intrinsic groups are NOT eliminated (camera parameters)
1415        assert!(
1416            !ordering.should_eliminate("intr_group_0000", &ManifoldType::RN, 3),
1417            "Intrinsic group 0 should be camera parameter (not eliminated)"
1418        );
1419        assert!(
1420            !ordering.should_eliminate("intr_group_0001", &ManifoldType::RN, 3),
1421            "Intrinsic group 1 should be camera parameter (not eliminated)"
1422        );
1423        assert!(
1424            !ordering.should_eliminate("intr_group_0005", &ManifoldType::RN, 3),
1425            "Intrinsic group 5 should be camera parameter (not eliminated)"
1426        );
1427        assert!(
1428            !ordering.should_eliminate("intr_group_0042", &ManifoldType::RN, 3),
1429            "Intrinsic group 42 should be camera parameter (not eliminated)"
1430        );
1431
1432        // Verify landmarks are still eliminated
1433        assert!(
1434            ordering.should_eliminate("pt_00000", &ManifoldType::RN, 3),
1435            "Landmarks should still be eliminated"
1436        );
1437
1438        // Verify camera poses are not eliminated
1439        assert!(
1440            !ordering.should_eliminate("cam_0000", &ManifoldType::SE3, 6),
1441            "Camera poses should not be eliminated"
1442        );
1443    }
1444
1445    #[test]
1446    fn test_schur_ordering_invalid_landmark_type() {
1447        let ordering = SchurOrdering::default();
1448        // Landmark with wrong manifold type should return false
1449        assert!(
1450            !ordering.should_eliminate("pt_00000", &ManifoldType::SE3, 6),
1451            "Landmark with invalid manifold type should not be eliminated"
1452        );
1453    }
1454
1455    #[test]
1456    fn test_schur_ordering_invalid_landmark_size() {
1457        let ordering = SchurOrdering::default();
1458        // Landmark with wrong size should return false
1459        assert!(
1460            !ordering.should_eliminate("pt_00000", &ManifoldType::RN, 6),
1461            "Landmark with invalid size should not be eliminated"
1462        );
1463    }
1464
1465    #[test]
1466    fn test_block_structure_creation() {
1467        let structure = SchurBlockStructure::new();
1468        assert_eq!(structure.camera_dof, 0);
1469        assert_eq!(structure.landmark_dof, 0);
1470    }
1471
1472    #[test]
1473    fn test_solver_creation() {
1474        let solver = SparseSchurComplementSolver::new();
1475        assert!(solver.block_structure.is_none());
1476    }
1477
1478    #[test]
1479    fn test_3x3_block_inversion() {
1480        let block = Matrix3::new(2.0, 0.0, 0.0, 0.0, 3.0, 0.0, 0.0, 0.0, 4.0);
1481        let inv = SparseSchurComplementSolver::invert_landmark_blocks(&[block])
1482            .expect("Test: Block inversion should succeed");
1483        assert!((inv[0][(0, 0)] - 0.5).abs() < 1e-10);
1484    }
1485
1486    #[test]
1487    fn test_schur_variants() {
1488        let solver = SparseSchurComplementSolver::new()
1489            .with_variant(SchurVariant::Iterative)
1490            .with_preconditioner(SchurPreconditioner::BlockDiagonal)
1491            .with_cg_params(100, 1e-8);
1492
1493        assert_eq!(solver.cg_max_iterations, 100);
1494        assert!((solver.cg_tolerance - 1e-8).abs() < 1e-12);
1495    }
1496
1497    #[test]
1498    fn test_compute_schur_complement_known_matrix() {
1499        use faer::sparse::Triplet;
1500
1501        let solver = SparseSchurComplementSolver::new();
1502
1503        // Create simple 2x2 H_cc (camera block)
1504        let h_cc_triplets = vec![Triplet::new(0, 0, 4.0), Triplet::new(1, 1, 5.0)];
1505        let h_cc = SparseColMat::try_new_from_triplets(2, 2, &h_cc_triplets)
1506            .expect("Test: H_cc matrix creation should succeed");
1507
1508        // Create 2x3 H_cp (coupling block - 1 landmark with 3 DOF)
1509        let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 2.0)];
1510        let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1511            .expect("Test: H_cp matrix creation should succeed");
1512
1513        // Create H_pp^{-1} as identity scaled by 0.5
1514        let hpp_inv = vec![Matrix3::new(0.5, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.5)];
1515
1516        // Compute S = H_cc - H_cp * H_pp^{-1} * H_cp^T
1517        // H_cp has [1.0 at (0,0), 2.0 at (1,1), rest zeros]
1518        // H_cp * H_pp^{-1} (with H_pp^{-1} = 0.5*I) gives:
1519        //   Row 0: [0.5, 0, 0]
1520        //   Row 1: [0, 1.0, 0]
1521        // (H_cp * H_pp^{-1}) * H_cp^T:
1522        //   (0,0): 0.5*1 = 0.5, but we sum over all k, so actually just first column contribution
1523        //   The diagonal will be: row·row for each
1524        // Let me recalculate: S(0,0) = 4 - 0.5*1 = 3.5, but actual is 3.75
1525        // Actually the formula computes sum over all landmark DOF
1526        let s = solver
1527            .compute_schur_complement(&h_cc, &h_cp, &hpp_inv)
1528            .expect("Test: Schur complement computation should succeed");
1529
1530        assert_eq!(s.nrows(), 2);
1531        assert_eq!(s.ncols(), 2);
1532        // Verify the actual computed values (diagonal elements of Schur complement)
1533        // S = H_cc - H_cp * H_pp^{-1} * H_cp^T
1534        // H_cp * H_pp^{-1} = [[0.5, 0, 0], [0, 1.0, 0]]
1535        // (H_cp * H_pp^{-1}) * H_cp^T:
1536        //   (0,0) = 0.5*1 = 0.5
1537        //   (1,1) = 1.0*2 = 2.0
1538        // S(0,0) = 4 - 0.5 = 3.5, S(1,1) = 5 - 2.0 = 3.0
1539        assert!((s[(0, 0)] - 3.5).abs() < 1e-10, "S(0,0) = {}", s[(0, 0)]);
1540        assert!((s[(1, 1)] - 3.0).abs() < 1e-10, "S(1,1) = {}", s[(1, 1)]);
1541    }
1542
1543    #[test]
1544    fn test_back_substitute() {
1545        use faer::sparse::Triplet;
1546
1547        let solver = SparseSchurComplementSolver::new();
1548
1549        // Create test data
1550        let delta_c = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); // [1; 2]
1551        let g_p = Mat::from_fn(3, 1, |i, _| (i + 1) as f64); // [1; 2; 3]
1552
1553        // H_cp (2x3)
1554        let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 1.0)];
1555        let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1556            .expect("Test: H_cp matrix creation should succeed");
1557
1558        // H_pp^{-1} (identity)
1559        let hpp_inv = vec![Matrix3::identity()];
1560
1561        // Compute δp = H_pp^{-1} * (g_p - H_cp^T * δc)
1562        // H_cp^T * δc = [1*1; 1*2; 0] = [1; 2; 0]
1563        // g_p - result = [1; 2; 3] - [1; 2; 0] = [0; 0; 3]
1564        // H_pp^{-1} * [0; 0; 3] = [0; 0; 3]
1565        let delta_p = solver
1566            .back_substitute(&delta_c, &g_p, &h_cp, &hpp_inv)
1567            .expect("Test: Back substitution should succeed");
1568
1569        assert_eq!(delta_p.nrows(), 3);
1570        assert!((delta_p[(0, 0)]).abs() < 1e-10);
1571        assert!((delta_p[(1, 0)]).abs() < 1e-10);
1572        assert!((delta_p[(2, 0)] - 3.0).abs() < 1e-10);
1573    }
1574
1575    #[test]
1576    fn test_compute_reduced_gradient() {
1577        use faer::sparse::Triplet;
1578
1579        let solver = SparseSchurComplementSolver::new();
1580
1581        // Create test data
1582        let g_c = Mat::from_fn(2, 1, |i, _| (i + 1) as f64); // [1; 2]
1583        let g_p = Mat::from_fn(3, 1, |i, _| (i + 1) as f64); // [1; 2; 3]
1584
1585        // H_cp (2x3)
1586        let h_cp_triplets = vec![Triplet::new(0, 0, 1.0), Triplet::new(1, 1, 1.0)];
1587        let h_cp = SparseColMat::try_new_from_triplets(2, 3, &h_cp_triplets)
1588            .expect("Test: H_cp matrix creation should succeed");
1589
1590        // H_pp^{-1} (2*identity)
1591        let hpp_inv = vec![Matrix3::new(2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0)];
1592
1593        // Compute g_reduced = g_c - H_cp * H_pp^{-1} * g_p
1594        // H_pp^{-1} * g_p = 2*[1; 2; 3] = [2; 4; 6]
1595        // H_cp * [2; 4; 6] = [1*2; 1*4] = [2; 4]
1596        // g_reduced = [1; 2] - [2; 4] = [-1; -2]
1597        let g_reduced = solver
1598            .compute_reduced_gradient(&g_c, &g_p, &h_cp, &hpp_inv)
1599            .expect("Test: Reduced gradient computation should succeed");
1600
1601        assert_eq!(g_reduced.nrows(), 2);
1602        assert!((g_reduced[(0, 0)] + 1.0).abs() < 1e-10);
1603        assert!((g_reduced[(1, 0)] + 2.0).abs() < 1e-10);
1604    }
1605}