apex-solver 1.3.0

High-performance nonlinear least squares optimization with Lie group support for SLAM and bundle adjustment
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
1421
1422
1423
1424
1425
1426
1427
1428
1429
1430
1431
1432
1433
1434
1435
1436
1437
1438
1439
1440
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
1481
1482
1483
1484
1485
1486
1487
1488
1489
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
1518
1519
1520
1521
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
1544
1545
1546
1547
1548
1549
//! # Implicit Schur Complement Solver
//!
//! This module implements the **Implicit Schur Complement** method using matrix-free
//! Preconditioned Conjugate Gradients (PCG) for bundle adjustment.
//!
//! ## Explicit vs Implicit Schur Complement
//!
//! **Implicit Schur:** This formulation never constructs the reduced camera matrix S
//! explicitly. Instead, it solves the linear system using a matrix-free approach where
//! only the matrix-vector product S·x is computed. This is highly memory-efficient for
//! large-scale problems.
//!
//! **Explicit Schur:** The alternative formulation (see [`explicit_schur`](super::explicit_schur))
//! physically constructs S = B - E C⁻¹ Eᵀ in memory and uses sparse Cholesky factorization.
//!
//! ## When to Use Implicit Schur
//!
//! - Very large bundle adjustment problems (> 10,000 cameras)
//! - Memory-constrained environments
//! - When iterative methods converge well (good preconditioning)
//! - When the reduced camera system S is too large to store explicitly
//!
//! ## Algorithm
//!
//! 1. Form Schur complement implicitly: S = H_cc - H_cp * H_pp^{-1} * H_cp^T
//! 2. Solve S*δc = g_reduced using PCG (matrix-free)
//! 3. Back-substitute: δp = H_pp^{-1} * (g_p - H_cp^T * δc)
//!
//! ## Usage Example
//!
//! ```no_run
//! # use apex_solver::linalg::{SparseSchurComplementSolver, SchurVariant, SchurPreconditioner};
//! # use apex_solver::linalg::StructureAware;
//! # use std::collections::HashMap;
//! # fn example() -> Result<(), Box<dyn std::error::Error>> {
//! # let variables = HashMap::new();
//! # let variable_index_map = HashMap::new();
//! use apex_solver::linalg::{SparseSchurComplementSolver, SchurVariant, SchurPreconditioner};
//! use apex_solver::linalg::StructureAware;
//!
//! let mut solver = SparseSchurComplementSolver::new()
//!     .with_variant(SchurVariant::Iterative) // Implicit Schur with PCG
//!     .with_preconditioner(SchurPreconditioner::SchurJacobi); // Recommended for PCG
//! solver.initialize_structure(&variables, &variable_index_map)?;
//! # Ok(())
//! # }
//! ```

use super::explicit_schur::{SchurBlockStructure, SchurOrdering, SchurPreconditioner};
use crate::core::problem::VariableEnum;
use crate::linalg::{LinAlgError, LinAlgResult, LinearSolver, SparseMode, StructureAware};
use faer::Mat;
use faer::sparse::{SparseColMat, Triplet};
use nalgebra::{DMatrix, DVector, Matrix3};
use rayon::prelude::*;
use std::collections::HashMap;
use std::ops::Mul;

/// Iterative Schur complement solver using Preconditioned Conjugate Gradients
#[derive(Debug, Clone)]
pub struct IterativeSchurSolver {
    block_structure: Option<SchurBlockStructure>,
    ordering: SchurOrdering,

    // CG parameters
    max_cg_iterations: usize,
    cg_tolerance: f64,

    // Preconditioner type
    preconditioner_type: SchurPreconditioner,

    // Cached for matrix-vector products
    landmark_block_inverses: Vec<Matrix3<f64>>,
    hessian: Option<SparseColMat<usize, f64>>,
    gradient: Option<Mat<f64>>,

    // Workspace buffers for Schur operator (avoid repeated allocations)
    workspace_lm: Vec<f64>,  // landmark DOF sized buffer
    workspace_cam: Vec<f64>, // camera DOF sized buffer

    // Visibility index: camera_block_idx -> Vec<landmark_block_idx>
    // This avoids O(cameras * landmarks) iteration in preconditioner computation
    camera_to_landmark_visibility: Vec<Vec<usize>>,
}

impl IterativeSchurSolver {
    /// Create a new iterative Schur solver with default parameters
    /// Default: Schur-Jacobi preconditioner, 500 max iterations, 1e-9 relative tolerance
    /// These tighter settings match Ceres Solver behavior for accurate step computation.
    pub fn new() -> Self {
        Self {
            block_structure: None,
            ordering: SchurOrdering::default(),
            max_cg_iterations: 500, // More iterations for large BA problems
            cg_tolerance: 1e-9,     // Tighter tolerance for accurate steps
            preconditioner_type: SchurPreconditioner::SchurJacobi,
            landmark_block_inverses: Vec::new(),
            hessian: None,
            gradient: None,
            workspace_lm: Vec::new(),
            workspace_cam: Vec::new(),
            camera_to_landmark_visibility: Vec::new(),
        }
    }

    /// Create solver with custom CG parameters
    pub fn with_cg_params(max_iterations: usize, tolerance: f64) -> Self {
        Self {
            block_structure: None,
            ordering: SchurOrdering::default(),
            max_cg_iterations: max_iterations,
            cg_tolerance: tolerance,
            preconditioner_type: SchurPreconditioner::SchurJacobi,
            landmark_block_inverses: Vec::new(),
            hessian: None,
            gradient: None,
            workspace_lm: Vec::new(),
            workspace_cam: Vec::new(),
            camera_to_landmark_visibility: Vec::new(),
        }
    }

    /// Create solver with full configuration
    pub fn with_config(
        max_iterations: usize,
        tolerance: f64,
        preconditioner: SchurPreconditioner,
    ) -> Self {
        Self {
            block_structure: None,
            ordering: SchurOrdering::default(),
            max_cg_iterations: max_iterations,
            cg_tolerance: tolerance,
            preconditioner_type: preconditioner,
            landmark_block_inverses: Vec::new(),
            hessian: None,
            gradient: None,
            workspace_lm: Vec::new(),
            workspace_cam: Vec::new(),
            camera_to_landmark_visibility: Vec::new(),
        }
    }

    /// Initialize workspace buffers based on problem dimensions
    fn init_workspaces(&mut self) {
        if let Some(structure) = &self.block_structure {
            let lm_dof = structure.landmark_dof;
            let cam_dof = structure.camera_dof;

            if self.workspace_lm.len() != lm_dof {
                self.workspace_lm = vec![0.0; lm_dof];
            }
            if self.workspace_cam.len() != cam_dof {
                self.workspace_cam = vec![0.0; cam_dof];
            }
        }
    }

    /// Apply Schur complement operator: S*x = (H_cc - H_cp * H_pp^{-1} * H_cp^T) * x
    ///
    /// This computes the matrix-vector product without explicitly forming S.
    /// Uses workspace buffers to avoid allocations during PCG iterations.
    fn apply_schur_operator_fast(
        &self,
        x: &Mat<f64>,
        result: &mut Mat<f64>,
        temp_lm: &mut [f64],
        temp_cam: &mut [f64],
    ) -> LinAlgResult<()> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let hessian = self
            .hessian
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;

        let symbolic = hessian.symbolic();
        let (cam_start, cam_end) = structure.camera_col_range();
        let (lm_start, lm_end) = structure.landmark_col_range();
        let cam_dof = structure.camera_dof;

        // Clear workspace buffers
        temp_lm.iter_mut().for_each(|v| *v = 0.0);
        temp_cam.iter_mut().for_each(|v| *v = 0.0);

        // Fused Step 1+2: result = H_cc * x AND temp_lm = H_cp^T * x
        // Process camera columns once, extracting both products
        for col in cam_start..cam_end {
            let local_col = col - cam_start;
            let x_val = x[(local_col, 0)];
            let row_indices = symbolic.row_idx_of_col_raw(col);
            let col_values = hessian.val_of_col(col);

            for (idx, &row) in row_indices.iter().enumerate() {
                let val = col_values[idx];
                if row >= cam_start && row < cam_end {
                    // H_cc contribution
                    let local_row = row - cam_start;
                    result[(local_row, 0)] += val * x_val;
                } else if row >= lm_start && row < lm_end {
                    // H_cp^T contribution (camera col -> landmark row)
                    let local_row = row - lm_start;
                    temp_lm[local_row] += val * x_val;
                }
            }
        }

        // Step 3: Apply H_pp^{-1} in-place: temp_lm = H_pp^{-1} * temp_lm
        for (block_idx, (_, start_col, _)) in structure.landmark_blocks.iter().enumerate() {
            let inv_block = &self.landmark_block_inverses[block_idx];
            let local_start = start_col - lm_start;

            // Read input values
            let in0 = temp_lm[local_start];
            let in1 = temp_lm[local_start + 1];
            let in2 = temp_lm[local_start + 2];

            // Apply 3x3 inverse block
            temp_lm[local_start] =
                inv_block[(0, 0)] * in0 + inv_block[(0, 1)] * in1 + inv_block[(0, 2)] * in2;
            temp_lm[local_start + 1] =
                inv_block[(1, 0)] * in0 + inv_block[(1, 1)] * in1 + inv_block[(1, 2)] * in2;
            temp_lm[local_start + 2] =
                inv_block[(2, 0)] * in0 + inv_block[(2, 1)] * in1 + inv_block[(2, 2)] * in2;
        }

        // Step 4: temp_cam = H_cp * temp_lm (iterate over landmark columns)
        for col in lm_start..lm_end {
            let local_col = col - lm_start;
            let lm_val = temp_lm[local_col];
            let row_indices = symbolic.row_idx_of_col_raw(col);
            let col_values = hessian.val_of_col(col);

            for (idx, &row) in row_indices.iter().enumerate() {
                if row >= cam_start && row < cam_end {
                    let local_row = row - cam_start;
                    temp_cam[local_row] += col_values[idx] * lm_val;
                }
            }
        }

        // Step 5: result = result - temp_cam = H_cc*x - H_cp*H_pp^{-1}*H_cp^T*x
        for i in 0..cam_dof {
            result[(i, 0)] -= temp_cam[i];
        }

        Ok(())
    }

    /// Extract H_cp^T and multiply with vector: (H_cp^T) * x
    fn extract_camera_landmark_transpose_mvp(
        &self,
        hessian: &SparseColMat<usize, f64>,
        x: &Mat<f64>,
    ) -> LinAlgResult<Mat<f64>> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
        let (cam_start, cam_end) = structure.camera_col_range();
        let (lm_start, lm_end) = structure.landmark_col_range();
        let lm_dof = structure.landmark_dof;

        let mut result = Mat::<f64>::zeros(lm_dof, 1);
        let symbolic = hessian.symbolic();

        // H_cp^T * x = iterate over camera columns, accumulate into landmark rows
        for col in cam_start..cam_end {
            let local_col = col - cam_start;
            let row_indices = symbolic.row_idx_of_col_raw(col);
            let col_values = hessian.val_of_col(col);

            for (idx, &row) in row_indices.iter().enumerate() {
                if row >= lm_start && row < lm_end {
                    let local_row = row - lm_start;
                    result[(local_row, 0)] += col_values[idx] * x[(local_col, 0)];
                }
            }
        }

        Ok(result)
    }

    /// Extract H_cp and multiply with vector
    fn extract_camera_landmark_mvp(
        &self,
        hessian: &SparseColMat<usize, f64>,
        x: &Mat<f64>,
    ) -> LinAlgResult<Mat<f64>> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
        let (cam_start, cam_end) = structure.camera_col_range();
        let (lm_start, lm_end) = structure.landmark_col_range();
        let cam_dof = structure.camera_dof;

        let mut result = Mat::<f64>::zeros(cam_dof, 1);
        let symbolic = hessian.symbolic();

        // H_cp * x: iterate over landmark columns
        for col in lm_start..lm_end {
            let local_col = col - lm_start;
            let row_indices = symbolic.row_idx_of_col_raw(col);
            let col_values = hessian.val_of_col(col);

            for (idx, &row) in row_indices.iter().enumerate() {
                if row >= cam_start && row < cam_end {
                    let local_row = row - cam_start;
                    result[(local_row, 0)] += col_values[idx] * x[(local_col, 0)];
                }
            }
        }

        Ok(result)
    }

    /// Apply H_pp^{-1} using cached block inverses
    fn apply_landmark_inverse(&self, input: &Mat<f64>, output: &mut Mat<f64>) -> LinAlgResult<()> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        for (block_idx, (_, start_col, _)) in structure.landmark_blocks.iter().enumerate() {
            let inv_block = &self.landmark_block_inverses[block_idx];
            let local_start = start_col - structure.landmark_col_range().0;

            for i in 0..3 {
                let mut sum = 0.0;
                for j in 0..3 {
                    sum += inv_block[(i, j)] * input[(local_start + j, 0)];
                }
                output[(local_start + i, 0)] = sum;
            }
        }

        Ok(())
    }

    /// Compute block-Jacobi preconditioner: inverts camera diagonal blocks of H_cc only
    ///
    /// Instead of scalar diagonal (1/H_ii), this inverts the full camera blocks.
    /// For cameras with 6 DOF (SE3), this creates 6×6 inverse blocks.
    ///
    /// NOTE: This is NOT the true Schur-Jacobi preconditioner. It only uses
    /// diagonal blocks of H_cc, not the Schur complement S. For better convergence,
    /// use `compute_schur_jacobi_preconditioner()` instead.
    fn compute_block_preconditioner(&self) -> LinAlgResult<Vec<DMatrix<f64>>> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let hessian = self
            .hessian
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;

        let symbolic = hessian.symbolic();

        let mut precond_blocks = Vec::with_capacity(structure.camera_blocks.len());

        for (_, start_col, size) in &structure.camera_blocks {
            // Extract the diagonal block for this camera
            let mut block = DMatrix::<f64>::zeros(*size, *size);

            for local_col in 0..*size {
                let global_col = start_col + local_col;
                let row_indices = symbolic.row_idx_of_col_raw(global_col);
                let col_values = hessian.val_of_col(global_col);

                for (idx, &global_row) in row_indices.iter().enumerate() {
                    if global_row >= *start_col && global_row < start_col + size {
                        let local_row = global_row - start_col;
                        block[(local_row, local_col)] = col_values[idx];
                    }
                }
            }

            // Invert with regularization for numerical stability
            let inv_block = match block.clone().try_inverse() {
                Some(inv) => inv,
                None => {
                    // Add regularization and retry
                    let reg = 1e-6 * block.diagonal().iter().sum::<f64>().abs() / *size as f64;
                    let reg = reg.max(1e-8);
                    for i in 0..*size {
                        block[(i, i)] += reg;
                    }
                    block
                        .try_inverse()
                        .unwrap_or_else(|| DMatrix::identity(*size, *size))
                }
            };

            precond_blocks.push(inv_block);
        }

        Ok(precond_blocks)
    }

    /// Apply block-Jacobi preconditioner: z = M^{-1} * r
    ///
    /// For each camera block, multiply by the inverse block matrix.
    fn apply_block_preconditioner(
        &self,
        r: &Mat<f64>,
        precond_blocks: &[DMatrix<f64>],
    ) -> LinAlgResult<Mat<f64>> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let cam_dof = structure.camera_dof;
        let mut z = Mat::<f64>::zeros(cam_dof, 1);
        let cam_start = structure.camera_col_range().0;

        for (block_idx, (_, start_col, size)) in structure.camera_blocks.iter().enumerate() {
            let local_start = start_col - cam_start;
            let inv_block = &precond_blocks[block_idx];

            // Extract r block as DVector
            let mut r_block = DVector::<f64>::zeros(*size);
            for i in 0..*size {
                r_block[i] = r[(local_start + i, 0)];
            }

            // Apply inverse: z_block = M^{-1} * r_block
            let z_block = inv_block * r_block;

            // Write back to z
            for i in 0..*size {
                z[(local_start + i, 0)] = z_block[i];
            }
        }

        Ok(z)
    }

    /// Compute TRUE Schur-Jacobi preconditioner: diagonal blocks of the Schur complement S
    ///
    /// This is what Ceres Solver uses for SCHUR_JACOBI preconditioner.
    ///
    /// For each camera i:
    ///   S[i,i] = H_cc[i,i] - Σ_j H_cp[i,j] * H_pp[j,j]^{-1} * H_cp[i,j]^T
    ///
    /// where the sum is over all landmarks j observed by camera i.
    ///
    /// This preconditioner captures the effect of point elimination on each camera block,
    /// leading to much faster PCG convergence (typically 20-40 iterations vs 100+).
    fn compute_schur_jacobi_preconditioner(&self) -> LinAlgResult<Vec<DMatrix<f64>>> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let hessian = self
            .hessian
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Hessian not computed".into()))?;

        let symbolic = hessian.symbolic();

        // Borrow visibility index for use in parallel iterator
        let visibility = &self.camera_to_landmark_visibility;

        // Compute S[i,i] for each camera in parallel
        // S[i,i] = H_cc[i,i] - Σ_j H_cp[i,j] * H_pp[j,j]^{-1} * H_cp[i,j]^T
        // Using visibility index: only iterate over connected landmarks (O(observations) instead of O(cameras * landmarks))
        let precond_blocks: Vec<DMatrix<f64>> = structure
            .camera_blocks
            .par_iter()
            .enumerate()
            .map(|(cam_idx, (_, cam_col_start, cam_size))| {
                // Step 1: Extract H_cc[i,i] diagonal block
                let mut s_ii = DMatrix::<f64>::zeros(*cam_size, *cam_size);

                for local_col in 0..*cam_size {
                    let global_col = cam_col_start + local_col;
                    let row_indices = symbolic.row_idx_of_col_raw(global_col);
                    let col_values = hessian.val_of_col(global_col);

                    for (idx, &global_row) in row_indices.iter().enumerate() {
                        if global_row >= *cam_col_start && global_row < cam_col_start + cam_size {
                            let local_row = global_row - cam_col_start;
                            s_ii[(local_row, local_col)] = col_values[idx];
                        }
                    }
                }

                // Step 2: For each landmark OBSERVED by this camera (visibility-indexed)
                // This is the key optimization: O(avg_landmarks_per_camera) instead of O(all_landmarks)
                let visible_landmarks = if cam_idx < visibility.len() {
                    &visibility[cam_idx]
                } else {
                    &[] as &[usize]
                };

                for &lm_block_idx in visible_landmarks {
                    if lm_block_idx >= structure.landmark_blocks.len() {
                        continue;
                    }
                    let (_, lm_col_start, _) = &structure.landmark_blocks[lm_block_idx];

                    // Extract H_cp[i,j] block (cam_size x 3)
                    let mut h_cp = DMatrix::<f64>::zeros(*cam_size, 3);

                    for col_offset in 0..3 {
                        let global_col = lm_col_start + col_offset;
                        let row_indices = symbolic.row_idx_of_col_raw(global_col);
                        let col_values = hessian.val_of_col(global_col);

                        for (idx, &global_row) in row_indices.iter().enumerate() {
                            if global_row >= *cam_col_start && global_row < cam_col_start + cam_size
                            {
                                let local_row = global_row - cam_col_start;
                                h_cp[(local_row, col_offset)] = col_values[idx];
                            }
                        }
                    }

                    // Get H_pp[j,j]^{-1} from cached inverses
                    let hpp_inv = &self.landmark_block_inverses[lm_block_idx];

                    // Compute contribution: H_cp * H_pp^{-1} * H_cp^T
                    // First: temp = H_cp * H_pp^{-1} (cam_size x 3)
                    let mut temp = DMatrix::<f64>::zeros(*cam_size, 3);
                    for i in 0..*cam_size {
                        for j in 0..3 {
                            let mut sum = 0.0;
                            for k in 0..3 {
                                sum += h_cp[(i, k)] * hpp_inv[(k, j)];
                            }
                            temp[(i, j)] = sum;
                        }
                    }

                    // Then: contribution = temp * H_cp^T (cam_size x cam_size)
                    for i in 0..*cam_size {
                        for j in 0..*cam_size {
                            let mut sum = 0.0;
                            for k in 0..3 {
                                sum += temp[(i, k)] * h_cp[(j, k)];
                            }
                            s_ii[(i, j)] -= sum;
                        }
                    }
                }

                // Step 3: Invert S[i,i] with regularization if needed
                match s_ii.clone().try_inverse() {
                    Some(inv) => inv,
                    None => {
                        // Add regularization and retry
                        let trace = s_ii.trace();
                        let reg = (1e-6 * trace.abs() / *cam_size as f64).max(1e-8);
                        for i in 0..*cam_size {
                            s_ii[(i, i)] += reg;
                        }
                        s_ii.try_inverse()
                            .unwrap_or_else(|| DMatrix::identity(*cam_size, *cam_size))
                    }
                }
            })
            .collect();

        Ok(precond_blocks)
    }

    /// Solve S*x = b using Preconditioned Conjugate Gradients with block preconditioner
    /// Uses optimized Schur operator with workspace buffers to minimize allocations.
    fn solve_pcg_block(
        &self,
        b: &Mat<f64>,
        precond_blocks: &[DMatrix<f64>],
        workspace_lm: &mut [f64],
        workspace_cam: &mut [f64],
    ) -> LinAlgResult<Mat<f64>> {
        let cam_dof = b.nrows();
        let mut x = Mat::<f64>::zeros(cam_dof, 1);

        // r = b - S*x (x starts at 0, so r = b)
        let mut r = b.clone();

        // z = M^{-1} * r (block preconditioner)
        let mut z = self.apply_block_preconditioner(&r, precond_blocks)?;

        let mut p = z.clone();
        let mut rz_old = 0.0;
        for i in 0..cam_dof {
            rz_old += r[(i, 0)] * z[(i, 0)];
        }

        // Compute initial residual norm for relative convergence
        let b_norm: f64 = (0..cam_dof)
            .map(|i| b[(i, 0)] * b[(i, 0)])
            .sum::<f64>()
            .sqrt();
        let tol = self.cg_tolerance * b_norm.max(1.0);

        // Ap buffer (reused each iteration)
        let mut ap = Mat::<f64>::zeros(cam_dof, 1);

        for iter in 0..self.max_cg_iterations {
            // Ap = S * p (using fast operator with workspace buffers)
            // Reset ap to zeros
            for i in 0..cam_dof {
                ap[(i, 0)] = 0.0;
            }
            self.apply_schur_operator_fast(&p, &mut ap, workspace_lm, workspace_cam)?;

            // alpha = (r^T z) / (p^T Ap)
            let mut p_ap = 0.0;
            for i in 0..cam_dof {
                p_ap += p[(i, 0)] * ap[(i, 0)];
            }

            if p_ap.abs() < 1e-20 {
                tracing::debug!("PCG: p^T*A*p near zero at iteration {}", iter);
                break;
            }

            let alpha = rz_old / p_ap;

            // x = x + alpha * p
            for i in 0..cam_dof {
                x[(i, 0)] += alpha * p[(i, 0)];
            }

            // r = r - alpha * Ap
            for i in 0..cam_dof {
                r[(i, 0)] -= alpha * ap[(i, 0)];
            }

            // Check convergence
            let r_norm: f64 = (0..cam_dof)
                .map(|i| r[(i, 0)] * r[(i, 0)])
                .sum::<f64>()
                .sqrt();

            if r_norm < tol {
                tracing::debug!(
                    "PCG converged in {} iterations (residual={:.2e})",
                    iter + 1,
                    r_norm
                );
                break;
            }

            // z = M^{-1} * r (block preconditioner)
            z = self.apply_block_preconditioner(&r, precond_blocks)?;

            // beta = (r_{k+1}^T z_{k+1}) / (r_k^T z_k)
            let mut rz_new = 0.0;
            for i in 0..cam_dof {
                rz_new += r[(i, 0)] * z[(i, 0)];
            }

            if rz_old.abs() < 1e-30 {
                break;
            }

            let beta = rz_new / rz_old;

            // p = z + beta * p
            for i in 0..cam_dof {
                p[(i, 0)] = z[(i, 0)] + beta * p[(i, 0)];
            }

            rz_old = rz_new;
        }

        Ok(x)
    }

    /// Extract 3x3 diagonal blocks from H_pp and invert them with numerical robustness
    ///
    /// This function uses parallel processing for the block inversions (156K+ blocks).
    /// Each block's condition number is checked and regularization applied as needed.
    fn invert_landmark_blocks(&mut self, hessian: &SparseColMat<usize, f64>) -> LinAlgResult<()> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let symbolic = hessian.symbolic();

        // Step 1: Extract all 3x3 blocks (sequential - requires sparse matrix access)
        let blocks: Vec<(usize, Matrix3<f64>)> = structure
            .landmark_blocks
            .iter()
            .enumerate()
            .map(|(i, (_, start_col, _))| {
                let mut block = Matrix3::<f64>::zeros();

                for local_col in 0..3 {
                    let global_col = start_col + local_col;
                    let row_indices = symbolic.row_idx_of_col_raw(global_col);
                    let col_values = hessian.val_of_col(global_col);

                    for (idx, &row) in row_indices.iter().enumerate() {
                        if row >= *start_col && row < start_col + 3 {
                            let local_row = row - start_col;
                            block[(local_row, local_col)] = col_values[idx];
                        }
                    }
                }

                (i, block)
            })
            .collect();

        // Step 2: Invert all blocks in parallel
        // Thresholds for numerical robustness
        const CONDITION_THRESHOLD: f64 = 1e10;
        const MIN_EIGENVALUE_THRESHOLD: f64 = 1e-12;
        const REGULARIZATION_SCALE: f64 = 1e-6;

        let results: Vec<Result<Matrix3<f64>, (usize, String)>> = blocks
            .par_iter()
            .map(|(i, block)| {
                // Check conditioning and apply regularization if needed
                let eigenvalues = block.symmetric_eigenvalues();
                let min_ev = eigenvalues.min();
                let max_ev = eigenvalues.max();

                if min_ev < MIN_EIGENVALUE_THRESHOLD {
                    // Severely ill-conditioned: add strong regularization
                    let reg = REGULARIZATION_SCALE + max_ev * REGULARIZATION_SCALE;
                    let regularized = block + Matrix3::identity() * reg;
                    regularized.try_inverse().ok_or_else(|| {
                        (
                            *i,
                            format!("singular even with regularization (min_ev={:.2e})", min_ev),
                        )
                    })
                } else if max_ev / min_ev > CONDITION_THRESHOLD {
                    // Ill-conditioned: add moderate regularization
                    let extra_reg = max_ev * REGULARIZATION_SCALE;
                    let regularized = block + Matrix3::identity() * extra_reg;
                    regularized.try_inverse().ok_or_else(|| {
                        (
                            *i,
                            format!("ill-conditioned (cond={:.2e})", max_ev / min_ev),
                        )
                    })
                } else {
                    // Well-conditioned: standard inversion
                    block
                        .try_inverse()
                        .ok_or_else(|| (*i, "singular".to_string()))
                }
            })
            .collect();

        // Step 3: Collect results and check for errors
        self.landmark_block_inverses.clear();
        self.landmark_block_inverses.reserve(results.len());

        for result in results {
            match result {
                Ok(inv) => self.landmark_block_inverses.push(inv),
                Err((i, msg)) => {
                    return Err(LinAlgError::SingularMatrix(format!(
                        "Landmark block {} {}",
                        i, msg
                    )));
                }
            }
        }

        Ok(())
    }

    /// Build camera->landmark visibility index from H_cp structure
    ///
    /// This scans the Hessian to find which landmarks each camera observes,
    /// enabling O(observations) preconditioner computation instead of O(cameras * landmarks).
    fn build_visibility_index(&mut self, hessian: &SparseColMat<usize, f64>) -> LinAlgResult<()> {
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;

        let symbolic = hessian.symbolic();
        let (cam_start, cam_end) = structure.camera_col_range();
        let num_cameras = structure.camera_blocks.len();

        // Build a map from global camera row -> camera block index
        let mut cam_row_to_block: HashMap<usize, usize> = HashMap::new();
        for (cam_idx, (_, start_col, size)) in structure.camera_blocks.iter().enumerate() {
            for offset in 0..*size {
                cam_row_to_block.insert(start_col + offset, cam_idx);
            }
        }

        // Initialize visibility: one vec per camera
        let mut visibility: Vec<Vec<usize>> = vec![Vec::new(); num_cameras];

        // Scan landmark columns to find camera connections
        for (lm_block_idx, (_, lm_col_start, _)) in structure.landmark_blocks.iter().enumerate() {
            // Check first column of this landmark block (all 3 columns have same row pattern)
            let global_col = *lm_col_start;
            if global_col >= hessian.ncols() {
                continue;
            }

            let row_indices = symbolic.row_idx_of_col_raw(global_col);

            // Find which cameras observe this landmark
            for &row in row_indices {
                if row >= cam_start
                    && row < cam_end
                    && let Some(&cam_idx) = cam_row_to_block.get(&row)
                {
                    // Only add if not already present (avoid duplicates)
                    if visibility[cam_idx].last() != Some(&lm_block_idx) {
                        visibility[cam_idx].push(lm_block_idx);
                    }
                }
            }
        }

        self.camera_to_landmark_visibility = visibility;
        Ok(())
    }

    /// Internal solve using the already-cached Hessian and gradient.
    /// This avoids rebuilding the Hessian which would lose the damping from solve_augmented_equation.
    fn solve_with_cached_hessian(&mut self) -> LinAlgResult<Mat<f64>> {
        let hessian = self
            .hessian
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Hessian not cached".into()))?
            .clone();
        let gradient = self
            .gradient
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Gradient not cached".into()))?
            .clone();

        // Extract structure info
        let structure = self
            .block_structure
            .as_ref()
            .ok_or_else(|| LinAlgError::InvalidInput("Block structure not initialized".into()))?;
        let cam_dof = structure.camera_dof;
        let lm_dof = structure.landmark_dof;
        let (cam_start, _cam_end) = structure.camera_col_range();
        let (lm_start, _lm_end) = structure.landmark_col_range();

        // Invert landmark blocks
        self.invert_landmark_blocks(&hessian)?;

        // Build visibility index for efficient preconditioner computation
        self.build_visibility_index(&hessian)?;

        // Extract reduced RHS: g_c - H_cp * H_pp^{-1} * g_p
        let mut g_reduced = Mat::<f64>::zeros(cam_dof, 1);
        for i in 0..cam_dof {
            g_reduced[(i, 0)] = gradient[(cam_start + i, 0)];
        }

        let mut g_lm = Mat::<f64>::zeros(lm_dof, 1);
        for i in 0..lm_dof {
            g_lm[(i, 0)] = gradient[(lm_start + i, 0)];
        }

        let mut temp = Mat::<f64>::zeros(lm_dof, 1);
        self.apply_landmark_inverse(&g_lm, &mut temp)?;

        let correction = self.extract_camera_landmark_mvp(&hessian, &temp)?;
        for i in 0..cam_dof {
            g_reduced[(i, 0)] -= correction[(i, 0)];
        }

        // Initialize workspace buffers if needed
        self.init_workspaces();

        // Solve S*δc = g_reduced using PCG with appropriate preconditioner
        let precond_blocks = match self.preconditioner_type {
            SchurPreconditioner::SchurJacobi => {
                // True Schur-Jacobi: diagonal blocks of S (Ceres-style, best convergence)
                self.compute_schur_jacobi_preconditioner()?
            }
            SchurPreconditioner::BlockDiagonal => {
                // Block diagonal of H_cc only (faster to compute, worse convergence)
                self.compute_block_preconditioner()?
            }
            SchurPreconditioner::None => {
                // Identity preconditioner (for debugging)
                let structure = self.block_structure.as_ref().ok_or_else(|| {
                    LinAlgError::InvalidInput("Block structure not initialized".into())
                })?;
                structure
                    .camera_blocks
                    .iter()
                    .map(|(_, _, size)| DMatrix::identity(*size, *size))
                    .collect()
            }
        };

        // Use workspace buffers for PCG iterations
        let mut workspace_lm = std::mem::take(&mut self.workspace_lm);
        let mut workspace_cam = std::mem::take(&mut self.workspace_cam);

        let delta_cam = self.solve_pcg_block(
            &g_reduced,
            &precond_blocks,
            &mut workspace_lm,
            &mut workspace_cam,
        )?;

        // Restore workspace buffers
        self.workspace_lm = workspace_lm;
        self.workspace_cam = workspace_cam;

        // Back-substitute for landmarks
        let hcp_t_delta_cam = self.extract_camera_landmark_transpose_mvp(&hessian, &delta_cam)?;

        let mut rhs_lm = Mat::<f64>::zeros(lm_dof, 1);
        for i in 0..lm_dof {
            rhs_lm[(i, 0)] = g_lm[(i, 0)] - hcp_t_delta_cam[(i, 0)];
        }

        let mut delta_lm = Mat::<f64>::zeros(lm_dof, 1);
        self.apply_landmark_inverse(&rhs_lm, &mut delta_lm)?;

        // Combine camera and landmark updates
        let total_dof = cam_dof + lm_dof;
        let mut delta = Mat::<f64>::zeros(total_dof, 1);

        for i in 0..cam_dof {
            delta[(cam_start + i, 0)] = delta_cam[(i, 0)];
        }
        for i in 0..lm_dof {
            delta[(lm_start + i, 0)] = delta_lm[(i, 0)];
        }

        Ok(delta)
    }
}

impl Default for IterativeSchurSolver {
    fn default() -> Self {
        Self::new()
    }
}

impl StructureAware for IterativeSchurSolver {
    fn initialize_structure(
        &mut self,
        variables: &HashMap<String, VariableEnum>,
        variable_index_map: &HashMap<String, usize>,
    ) -> LinAlgResult<()> {
        let mut structure = SchurBlockStructure::new();

        for (name, variable) in variables {
            let manifold_type = variable.manifold_type();
            let start_col = *variable_index_map.get(name).ok_or_else(|| {
                LinAlgError::InvalidInput(format!("Variable {} not in index map", name))
            })?;
            let size = variable.get_size();

            if self.ordering.should_eliminate(name, &manifold_type, size) {
                structure
                    .landmark_blocks
                    .push((name.clone(), start_col, size));
                structure.landmark_dof += size;

                if size != 3 {
                    return Err(LinAlgError::InvalidInput(format!(
                        "Landmark {} has DOF {}, expected 3",
                        name, size
                    )));
                }
                structure.num_landmarks += 1;
            } else {
                structure
                    .camera_blocks
                    .push((name.clone(), start_col, size));
                structure.camera_dof += size;
            }
        }

        structure.camera_blocks.sort_by_key(|(_, col, _)| *col);
        structure.landmark_blocks.sort_by_key(|(_, col, _)| *col);

        if structure.camera_blocks.is_empty() {
            return Err(LinAlgError::InvalidInput(
                "No camera variables found".into(),
            ));
        }
        if structure.landmark_blocks.is_empty() {
            return Err(LinAlgError::InvalidInput(
                "No landmark variables found".into(),
            ));
        }

        self.block_structure = Some(structure);
        Ok(())
    }
}

impl LinearSolver<SparseMode> for IterativeSchurSolver {
    fn solve_normal_equation(
        &mut self,
        residuals: &Mat<f64>,
        jacobian: &SparseColMat<usize, f64>,
    ) -> LinAlgResult<Mat<f64>> {
        // Build H = J^T * J, g = -J^T * r
        let jt = jacobian
            .transpose()
            .to_col_major()
            .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
        let hessian = jt.mul(jacobian);
        let jtr = jacobian.transpose().mul(residuals);
        let mut gradient = Mat::<f64>::zeros(jtr.nrows(), 1);
        for i in 0..jtr.nrows() {
            gradient[(i, 0)] = -jtr[(i, 0)];
        }

        self.hessian = Some(hessian);
        self.gradient = Some(gradient);

        // Solve using the cached Hessian
        self.solve_with_cached_hessian()
    }

    fn solve_augmented_equation(
        &mut self,
        residuals: &Mat<f64>,
        jacobian: &SparseColMat<usize, f64>,
        lambda: f64,
    ) -> LinAlgResult<Mat<f64>> {
        // Build H = J^T * J + λI
        let jt = jacobian
            .transpose()
            .to_col_major()
            .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?;
        let jtr = jt.mul(residuals);
        let mut hessian = jacobian
            .transpose()
            .to_col_major()
            .map_err(|e| LinAlgError::MatrixConversion(format!("Transpose failed: {:?}", e)))?
            .mul(jacobian);

        // Add damping to diagonal
        let n = hessian.ncols();
        let symbolic = hessian.symbolic();
        let mut triplets = Vec::new();

        for col in 0..n {
            let row_indices = symbolic.row_idx_of_col_raw(col);
            let col_values = hessian.val_of_col(col);

            for (idx, &row) in row_indices.iter().enumerate() {
                triplets.push(Triplet::new(row, col, col_values[idx]));
            }

            // Add lambda to diagonal
            triplets.push(Triplet::new(col, col, lambda));
        }

        hessian = SparseColMat::try_new_from_triplets(n, n, &triplets).map_err(|e| {
            LinAlgError::InvalidInput(format!("Failed to build damped Hessian: {:?}", e))
        })?;

        let mut gradient = Mat::<f64>::zeros(jtr.nrows(), 1);
        for i in 0..jtr.nrows() {
            gradient[(i, 0)] = -jtr[(i, 0)];
        }

        self.hessian = Some(hessian);
        self.gradient = Some(gradient.clone());

        // Solve using the cached damped Hessian (don't call solve_normal_equation
        // which would rebuild the Hessian without damping)
        self.solve_with_cached_hessian()
    }

    fn get_hessian(&self) -> Option<&SparseColMat<usize, f64>> {
        self.hessian.as_ref()
    }

    fn get_gradient(&self) -> Option<&Mat<f64>> {
        self.gradient.as_ref()
    }
}

#[cfg(test)]
mod tests {
    use super::*;
    use crate::core::variable::Variable;
    use apex_manifolds::{rn, se3};

    type TestResult = Result<(), Box<dyn std::error::Error>>;

    type TestSetup = (
        HashMap<String, VariableEnum>,
        HashMap<String, usize>,
        SparseColMat<usize, f64>,
        faer::Mat<f64>,
    );

    /// Build the same 2-camera + 3-landmark test setup used in explicit_schur tests.
    /// Jacobian: 36 rows × 21 cols  (H_cc = 3·I₁₂, H_pp = 4·I₃ — positive definite)
    fn create_schur_test_setup() -> Result<TestSetup, Box<dyn std::error::Error>> {
        let se3_id = DVector::from_vec(vec![1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]);
        let pt_zero = DVector::from_vec(vec![0.0, 0.0, 0.0]);

        let mut variables: HashMap<String, VariableEnum> = HashMap::new();
        variables.insert(
            "cam_0".to_string(),
            VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
        );
        variables.insert(
            "cam_1".to_string(),
            VariableEnum::SE3(Variable::new(se3::SE3::from(se3_id.clone()))),
        );
        variables.insert(
            "pt_0".to_string(),
            VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
        );
        variables.insert(
            "pt_1".to_string(),
            VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
        );
        variables.insert(
            "pt_2".to_string(),
            VariableEnum::Rn(Variable::new(rn::Rn::from(pt_zero.clone()))),
        );

        let mut variable_index_map: HashMap<String, usize> = HashMap::new();
        variable_index_map.insert("cam_0".to_string(), 0);
        variable_index_map.insert("cam_1".to_string(), 6);
        variable_index_map.insert("pt_0".to_string(), 12);
        variable_index_map.insert("pt_1".to_string(), 15);
        variable_index_map.insert("pt_2".to_string(), 18);

        // Jacobian: 2 cameras × 3 landmarks × 6 rows_per_obs = 36 rows, 21 cols
        let cam_cols = [0usize, 6];
        let lm_cols = [12usize, 15, 18];
        let mut triplets: Vec<Triplet<usize, usize, f64>> = Vec::new();
        for (ci, &cam_col) in cam_cols.iter().enumerate() {
            for (li, &lm_col) in lm_cols.iter().enumerate() {
                let row_base = (ci * 3 + li) * 6;
                for k in 0..6 {
                    triplets.push(Triplet::new(row_base + k, cam_col + k, 1.0));
                    triplets.push(Triplet::new(row_base + k, lm_col + (k % 3), 1.0));
                }
            }
        }

        let jacobian = SparseColMat::try_new_from_triplets(36, 21, &triplets)?;
        let residuals = faer::Mat::from_fn(36, 1, |i, _| (i % 5) as f64 * 0.1);

        Ok((variables, variable_index_map, jacobian, residuals))
    }

    #[test]
    fn test_iterative_schur_creation() {
        let solver = IterativeSchurSolver::new();
        // Default: 500 max iterations, 1e-9 tolerance, Schur-Jacobi preconditioner
        assert_eq!(solver.max_cg_iterations, 500);
        assert_eq!(solver.cg_tolerance, 1e-9);
        assert_eq!(solver.preconditioner_type, SchurPreconditioner::SchurJacobi);
    }

    #[test]
    fn test_with_custom_params() {
        let solver = IterativeSchurSolver::with_cg_params(100, 1e-8);
        assert_eq!(solver.max_cg_iterations, 100);
        assert_eq!(solver.cg_tolerance, 1e-8);
        // Should still use default Schur-Jacobi preconditioner
        assert_eq!(solver.preconditioner_type, SchurPreconditioner::SchurJacobi);
    }

    #[test]
    fn test_with_full_config() {
        let solver =
            IterativeSchurSolver::with_config(200, 1e-10, SchurPreconditioner::BlockDiagonal);
        assert_eq!(solver.max_cg_iterations, 200);
        assert_eq!(solver.cg_tolerance, 1e-10);
        assert_eq!(
            solver.preconditioner_type,
            SchurPreconditioner::BlockDiagonal
        );
    }

    // -------------------------------------------------------------------------
    // New tests for uncovered code paths
    // -------------------------------------------------------------------------

    /// Test Default impl equals new()
    #[test]
    fn test_iterative_schur_default() {
        let solver = IterativeSchurSolver::default();
        assert_eq!(solver.max_cg_iterations, 500);
        assert_eq!(solver.cg_tolerance, 1e-9);
        assert!(solver.block_structure.is_none());
        assert!(solver.hessian.is_none());
        assert!(solver.landmark_block_inverses.is_empty());
    }

    /// Test initialize_structure() partitions 2 cameras + 3 landmarks
    #[test]
    fn test_iterative_schur_initialize_structure() -> TestResult {
        let (variables, variable_index_map, _, _) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::new();
        solver.initialize_structure(&variables, &variable_index_map)?;

        let bs = solver
            .block_structure
            .as_ref()
            .ok_or("block_structure is None")?;
        assert_eq!(bs.camera_blocks.len(), 2);
        assert_eq!(bs.landmark_blocks.len(), 3);
        assert_eq!(bs.camera_dof, 12);
        assert_eq!(bs.landmark_dof, 9);
        Ok(())
    }

    /// Test full solve_normal_equation pipeline
    #[test]
    fn test_iterative_schur_solve_normal_equation() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        let delta =
            LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
        assert_eq!(delta.nrows(), 21);
        assert_eq!(delta.ncols(), 1);
        Ok(())
    }

    /// Test solve_augmented_equation (LM damping) pipeline
    #[test]
    fn test_iterative_schur_solve_augmented_equation() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        let delta = LinearSolver::<SparseMode>::solve_augmented_equation(
            &mut solver,
            &residuals,
            &jacobian,
            0.1,
        )?;
        assert_eq!(delta.nrows(), 21);
        Ok(())
    }

    /// Test get_hessian() and get_gradient() after solve
    #[test]
    fn test_iterative_schur_get_hessian_gradient() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        assert!(LinearSolver::<SparseMode>::get_hessian(&solver).is_none());
        assert!(LinearSolver::<SparseMode>::get_gradient(&solver).is_none());

        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        let h = LinearSolver::<SparseMode>::get_hessian(&solver);
        let g = LinearSolver::<SparseMode>::get_gradient(&solver);
        assert!(h.is_some());
        assert!(g.is_some());
        let h = h.ok_or("hessian is None")?;
        let g = g.ok_or("gradient is None")?;
        assert_eq!(h.nrows(), 21);
        assert_eq!(g.nrows(), 21);
        Ok(())
    }

    /// Test landmark_block_inverses populated after solve
    #[test]
    fn test_iterative_schur_invert_landmark_blocks() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        // Should have one 3×3 inverse per landmark (3 landmarks)
        assert_eq!(solver.landmark_block_inverses.len(), 3);
        Ok(())
    }

    /// Test visibility index populated after solve
    #[test]
    fn test_iterative_schur_build_visibility_index() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        // 2 cameras should each have visibility to some landmarks
        assert_eq!(solver.camera_to_landmark_visibility.len(), 2);
        for cam_visibility in &solver.camera_to_landmark_visibility {
            assert!(!cam_visibility.is_empty());
        }
        Ok(())
    }

    /// Test workspace buffers are allocated after solve
    #[test]
    fn test_iterative_schur_workspace_init() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;

        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        assert_eq!(solver.workspace_lm.len(), 9); // landmark DOF
        assert_eq!(solver.workspace_cam.len(), 12); // camera DOF
        Ok(())
    }

    /// Test BlockDiagonal preconditioner path
    #[test]
    fn test_iterative_schur_block_diagonal_preconditioner() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver =
            IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::BlockDiagonal);
        solver.initialize_structure(&variables, &variable_index_map)?;

        let delta =
            LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
        assert_eq!(delta.nrows(), 21);
        Ok(())
    }

    /// Test SchurJacobi preconditioner path
    #[test]
    fn test_iterative_schur_schur_jacobi_preconditioner() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver =
            IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::SchurJacobi);
        solver.initialize_structure(&variables, &variable_index_map)?;

        let delta =
            LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
        assert_eq!(delta.nrows(), 21);
        Ok(())
    }

    /// Test None preconditioner path
    #[test]
    fn test_iterative_schur_no_preconditioner() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::None);
        solver.initialize_structure(&variables, &variable_index_map)?;

        let delta =
            LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;
        assert_eq!(delta.nrows(), 21);
        Ok(())
    }

    /// Test two solves with different λ produce different updates
    #[test]
    fn test_iterative_schur_augmented_lambda_effect() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;

        let mut s1 = IterativeSchurSolver::with_cg_params(500, 1e-6);
        s1.initialize_structure(&variables, &variable_index_map)?;
        let d1 = LinearSolver::<SparseMode>::solve_augmented_equation(
            &mut s1, &residuals, &jacobian, 0.001,
        )?;

        let mut s2 = IterativeSchurSolver::with_cg_params(500, 1e-6);
        s2.initialize_structure(&variables, &variable_index_map)?;
        let d2 = LinearSolver::<SparseMode>::solve_augmented_equation(
            &mut s2, &residuals, &jacobian, 100.0,
        )?;

        let norm_diff: f64 = (0..21).map(|i| (d1[(i, 0)] - d2[(i, 0)]).powi(2)).sum();
        assert!(
            norm_diff > 1e-10,
            "Different λ should yield different updates"
        );
        Ok(())
    }

    /// Test solve without initialize_structure returns error
    #[test]
    fn test_iterative_schur_solve_without_init_returns_error() -> TestResult {
        let triplets: Vec<Triplet<usize, usize, f64>> = vec![Triplet::new(0, 0, 1.0)];
        let jacobian =
            SparseColMat::try_new_from_triplets(1, 1, &triplets).map_err(|e| format!("{e:?}"))?;
        let residuals = faer::Mat::from_fn(1, 1, |_, _| 1.0);
        let mut solver = IterativeSchurSolver::new();

        let result =
            LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian);
        assert!(result.is_err());
        Ok(())
    }

    // -------------------------------------------------------------------------
    // New tests for previously uncovered code paths
    // -------------------------------------------------------------------------

    /// Test apply_landmark_inverse applies the cached block inverses correctly.
    #[test]
    fn test_apply_landmark_inverse() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;
        // Run a solve to populate landmark_block_inverses
        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        // Input vector - landmark DOF (9 for 3 landmarks × 3)
        let input = faer::Mat::from_fn(9, 1, |i, _| (i + 1) as f64);
        let mut output = faer::Mat::zeros(9, 1);
        solver.apply_landmark_inverse(&input, &mut output)?;

        // The output should be non-zero (since the landmark blocks are non-trivial)
        let norm: f64 = (0..9).map(|i| output[(i, 0)].powi(2)).sum::<f64>().sqrt();
        assert!(
            norm > 0.0,
            "apply_landmark_inverse should produce non-zero output"
        );
        Ok(())
    }

    /// Test extract_camera_landmark_transpose_mvp produces a landmark-DOF output.
    #[test]
    fn test_extract_camera_landmark_transpose_mvp() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;
        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        let hessian = solver.hessian.as_ref().ok_or("hessian is None")?;

        // Camera-DOF input vector (12 entries for 2 cameras × 6 DOF)
        let x = faer::Mat::from_fn(12, 1, |i, _| (i as f64) * 0.1);
        let result = solver.extract_camera_landmark_transpose_mvp(hessian, &x)?;

        // Result should have landmark DOF = 9 rows
        assert_eq!(result.nrows(), 9);
        assert_eq!(result.ncols(), 1);
        Ok(())
    }

    /// Test extract_camera_landmark_mvp produces a camera-DOF output.
    #[test]
    fn test_extract_camera_landmark_mvp() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver = IterativeSchurSolver::with_cg_params(500, 1e-6);
        solver.initialize_structure(&variables, &variable_index_map)?;
        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        let hessian = solver.hessian.as_ref().ok_or("hessian is None")?;

        // Landmark-DOF input vector (9 entries for 3 landmarks × 3 DOF)
        let x = faer::Mat::from_fn(9, 1, |i, _| (i as f64) * 0.1);
        let result = solver.extract_camera_landmark_mvp(hessian, &x)?;

        // Result should have camera DOF = 12 rows
        assert_eq!(result.nrows(), 12);
        assert_eq!(result.ncols(), 1);
        Ok(())
    }

    /// Test apply_block_preconditioner produces correct-dimensional output.
    #[test]
    fn test_apply_block_preconditioner() -> TestResult {
        let (variables, variable_index_map, jacobian, residuals) = create_schur_test_setup()?;
        let mut solver =
            IterativeSchurSolver::with_config(500, 1e-6, SchurPreconditioner::BlockDiagonal);
        solver.initialize_structure(&variables, &variable_index_map)?;
        LinearSolver::<SparseMode>::solve_normal_equation(&mut solver, &residuals, &jacobian)?;

        // Compute the block preconditioner blocks
        let precond_blocks = solver.compute_block_preconditioner()?;
        // Should have one block per camera (2 cameras)
        assert_eq!(precond_blocks.len(), 2);

        // Apply to a camera-DOF residual vector
        let r = faer::Mat::from_fn(12, 1, |i, _| (i + 1) as f64);
        let z = solver.apply_block_preconditioner(&r, &precond_blocks)?;
        assert_eq!(z.nrows(), 12);
        assert_eq!(z.ncols(), 1);

        // The output should be non-zero
        let norm: f64 = (0..12).map(|i| z[(i, 0)].powi(2)).sum::<f64>().sqrt();
        assert!(norm > 0.0, "Preconditioned vector should be non-zero");
        Ok(())
    }

    /// Test initialize_structure returns Err when no camera variables are present.
    #[test]
    fn test_implicit_initialize_structure_no_cameras_returns_error() {
        use crate::core::variable::Variable;
        use apex_manifolds::rn;
        use nalgebra::DVector;

        let mut variables: HashMap<String, VariableEnum> = HashMap::new();
        variables.insert(
            "pt_0".to_string(),
            VariableEnum::Rn(Variable::new(rn::Rn::from(DVector::zeros(3)))),
        );
        let mut variable_index_map: HashMap<String, usize> = HashMap::new();
        variable_index_map.insert("pt_0".to_string(), 0);

        let mut solver = IterativeSchurSolver::new();
        let result = solver.initialize_structure(&variables, &variable_index_map);
        assert!(
            result.is_err(),
            "Expected Err when no camera variables present"
        );
    }

    /// Test initialize_structure returns Err when no landmark variables are present.
    #[test]
    fn test_implicit_initialize_structure_no_landmarks_returns_error() {
        use crate::core::variable::Variable;
        use apex_manifolds::se3;
        use nalgebra::DVector;

        let mut variables: HashMap<String, VariableEnum> = HashMap::new();
        variables.insert(
            "cam_0".to_string(),
            VariableEnum::SE3(Variable::new(se3::SE3::from(DVector::from_vec(vec![
                1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
            ])))),
        );
        let mut variable_index_map: HashMap<String, usize> = HashMap::new();
        variable_index_map.insert("cam_0".to_string(), 0);

        let mut solver = IterativeSchurSolver::new();
        let result = solver.initialize_structure(&variables, &variable_index_map);
        assert!(
            result.is_err(),
            "Expected Err when no landmark variables present"
        );
    }
}