1pub mod cpu;
26pub mod gpu;
27
28use std::{
29 collections::HashMap,
30 sync::{Arc, Mutex},
31};
32
33use faer::sparse::{SparseColMat, Triplet};
34use faer::{Col, Mat};
35use nalgebra::{DMatrix, DVector};
36use thiserror::Error;
37
38use crate::core::problem::{Problem, VariableEnum};
39use crate::error::ErrorLogging;
40use crate::{
41 core::{corrector::Corrector, residual_block::ResidualBlock},
42 linearizer::cpu::{DenseMode, LinearizationMode, SparseMode},
43};
44
45pub use cpu::sparse::SymbolicStructure;
46
47#[derive(Debug, Clone, Error)]
65pub enum LinearizerError {
66 #[error("Symbolic structure error: {0}")]
68 SymbolicStructure(String),
69
70 #[error("Parallel computation error: {0}")]
72 ParallelComputation(String),
73
74 #[error("Variable error: {0}")]
76 Variable(String),
77
78 #[error("Factor linearization failed: {0}")]
80 FactorLinearization(String),
81
82 #[error("Invalid input: {0}")]
84 InvalidInput(String),
85}
86
87pub type LinearizerResult<T> = Result<T, LinearizerError>;
89
90pub(crate) struct BlockLinearization {
99 pub jacobian: DMatrix<f64>,
101 pub variable_local_idx_size_list: Vec<(usize, usize)>,
103 pub residual_row_start_idx: usize,
105 pub residual_dim: usize,
107}
108
109pub(crate) fn linearize_block(
118 residual_block: &ResidualBlock,
119 variables: &HashMap<String, VariableEnum>,
120 total_residual: &Arc<Mutex<Col<f64>>>,
121) -> LinearizerResult<BlockLinearization> {
122 let mut param_vectors: Vec<DVector<f64>> = Vec::new();
123 let mut variable_local_idx_size_list = Vec::<(usize, usize)>::new();
124 let mut count_variable_local_idx: usize = 0;
125
126 for var_key in &residual_block.variable_key_list {
127 if let Some(variable) = variables.get(var_key) {
128 param_vectors.push(variable.to_vector());
129 let var_size = variable.get_size();
130 variable_local_idx_size_list.push((count_variable_local_idx, var_size));
131 count_variable_local_idx += var_size;
132 }
133 }
134
135 let (mut res, jac_opt) = residual_block.factor.linearize(¶m_vectors, true);
136 let mut jac = jac_opt.ok_or_else(|| {
137 LinearizerError::FactorLinearization(
138 "Factor returned None for Jacobian when compute_jacobian=true".to_string(),
139 )
140 .log()
141 })?;
142
143 if let Some(loss_func) = &residual_block.loss_func {
145 let squared_norm = res.dot(&res);
146 let corrector = Corrector::new(loss_func.as_ref(), squared_norm);
147 corrector.correct_jacobian(&res, &mut jac);
148 corrector.correct_residuals(&mut res);
149 }
150
151 let row_start = residual_block.residual_row_start_idx;
152 let dim = residual_block.factor.get_dimension();
153
154 {
156 let mut total_residual = total_residual.lock().map_err(|e| {
157 LinearizerError::ParallelComputation(
158 "Failed to acquire lock on total residual".to_string(),
159 )
160 .log_with_source(e)
161 })?;
162
163 let mut total_residual_mut = total_residual.as_mut();
164 for i in 0..dim {
165 total_residual_mut[row_start + i] = res[i];
166 }
167 }
168
169 Ok(BlockLinearization {
170 jacobian: jac,
171 variable_local_idx_size_list,
172 residual_row_start_idx: row_start,
173 residual_dim: dim,
174 })
175}
176
177pub trait AssemblyBackend: LinearizationMode {
192 fn assemble(
194 problem: &Problem,
195 variables: &HashMap<String, VariableEnum>,
196 variable_index_map: &HashMap<String, usize>,
197 symbolic_structure: Option<&SymbolicStructure>,
198 total_dof: usize,
199 ) -> LinearizerResult<(Mat<f64>, Self::Jacobian)>;
200
201 fn compute_column_norms(jacobian: &Self::Jacobian) -> Vec<f64>;
203
204 fn apply_column_scaling(jacobian: &Self::Jacobian, scaling: &[f64]) -> Self::Jacobian;
207
208 fn apply_inverse_scaling(step: &Mat<f64>, scaling: &[f64]) -> Mat<f64>;
210
211 fn hessian_vec_product(hessian: &Self::Hessian, vec: &Mat<f64>) -> Mat<f64>;
213}
214
215impl AssemblyBackend for SparseMode {
216 fn assemble(
217 problem: &Problem,
218 variables: &HashMap<String, VariableEnum>,
219 variable_index_map: &HashMap<String, usize>,
220 symbolic_structure: Option<&SymbolicStructure>,
221 _total_dof: usize,
222 ) -> LinearizerResult<(Mat<f64>, SparseColMat<usize, f64>)> {
223 let sym = symbolic_structure.ok_or_else(|| {
224 LinearizerError::InvalidInput("SparseMode requires symbolic structure".to_string())
225 })?;
226 crate::linearizer::cpu::sparse::assemble_sparse(problem, variables, variable_index_map, sym)
227 }
228
229 fn compute_column_norms(jacobian: &SparseColMat<usize, f64>) -> Vec<f64> {
230 let ncols = jacobian.ncols();
231 let sparse_ref = jacobian.as_ref();
232 (0..ncols)
233 .map(|c| {
234 let col_norm_squared: f64 =
235 sparse_ref.val_of_col(c).iter().map(|&val| val * val).sum();
236 col_norm_squared.sqrt()
237 })
238 .collect()
239 }
240
241 fn apply_column_scaling(
242 jacobian: &SparseColMat<usize, f64>,
243 scaling: &[f64],
244 ) -> SparseColMat<usize, f64> {
245 let ncols = jacobian.ncols();
246 let triplets: Vec<Triplet<usize, usize, f64>> =
247 (0..ncols).map(|c| Triplet::new(c, c, scaling[c])).collect();
248 let scaling_mat = match SparseColMat::try_new_from_triplets(ncols, ncols, &triplets) {
249 Ok(mat) => mat,
250 Err(_) => return jacobian.clone(),
251 };
252 jacobian * &scaling_mat
253 }
254
255 fn apply_inverse_scaling(step: &Mat<f64>, scaling: &[f64]) -> Mat<f64> {
256 let mut result = step.clone();
257 for i in 0..step.nrows() {
258 result[(i, 0)] *= scaling[i];
259 }
260 result
261 }
262
263 fn hessian_vec_product(hessian: &SparseColMat<usize, f64>, vec: &Mat<f64>) -> Mat<f64> {
264 use std::ops::Mul;
265 hessian.as_ref().mul(vec)
266 }
267}
268
269impl AssemblyBackend for DenseMode {
270 fn assemble(
271 problem: &Problem,
272 variables: &HashMap<String, VariableEnum>,
273 variable_index_map: &HashMap<String, usize>,
274 _symbolic_structure: Option<&SymbolicStructure>,
275 total_dof: usize,
276 ) -> LinearizerResult<(Mat<f64>, Mat<f64>)> {
277 crate::linearizer::cpu::dense::assemble_dense(
278 problem,
279 variables,
280 variable_index_map,
281 total_dof,
282 )
283 }
284
285 fn compute_column_norms(jacobian: &Mat<f64>) -> Vec<f64> {
286 let ncols = jacobian.ncols();
287 (0..ncols)
288 .map(|c| {
289 let mut norm_sq = 0.0;
290 for r in 0..jacobian.nrows() {
291 let v = jacobian[(r, c)];
292 norm_sq += v * v;
293 }
294 norm_sq.sqrt()
295 })
296 .collect()
297 }
298
299 fn apply_column_scaling(jacobian: &Mat<f64>, scaling: &[f64]) -> Mat<f64> {
300 let mut result = jacobian.clone();
301 for c in 0..jacobian.ncols() {
302 for r in 0..jacobian.nrows() {
303 result[(r, c)] *= scaling[c];
304 }
305 }
306 result
307 }
308
309 fn apply_inverse_scaling(step: &Mat<f64>, scaling: &[f64]) -> Mat<f64> {
310 let mut result = step.clone();
311 for i in 0..step.nrows() {
312 result[(i, 0)] *= scaling[i];
313 }
314 result
315 }
316
317 fn hessian_vec_product(hessian: &Mat<f64>, vec: &Mat<f64>) -> Mat<f64> {
318 hessian * vec
319 }
320}
321
322#[cfg(test)]
323mod tests {
324 use super::*;
325 use crate::{core::problem::Problem, factors, linalg::JacobianMode, optimizer};
326 use apex_manifolds::ManifoldType;
327 use faer::Col;
328 use nalgebra::{DMatrix, DVector, dvector};
329 use std::{
330 collections::HashMap,
331 sync::{Arc, Mutex},
332 };
333
334 type TestResult = Result<(), Box<dyn std::error::Error>>;
335
336 struct LinearFactor {
337 target: f64,
338 }
339
340 impl factors::Factor for LinearFactor {
341 fn linearize(
342 &self,
343 params: &[DVector<f64>],
344 compute_jacobian: bool,
345 ) -> (DVector<f64>, Option<DMatrix<f64>>) {
346 let residual = dvector![params[0][0] - self.target];
347 let jacobian = if compute_jacobian {
348 Some(DMatrix::from_element(1, 1, 1.0))
349 } else {
350 None
351 };
352 (residual, jacobian)
353 }
354
355 fn get_dimension(&self) -> usize {
356 1
357 }
358 }
359
360 fn one_var_problem() -> (Problem, HashMap<String, (ManifoldType, DVector<f64>)>) {
361 let mut problem = Problem::new(JacobianMode::Sparse);
362 problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 0.0 }), None);
363 let mut init = HashMap::new();
364 init.insert("x".to_string(), (ManifoldType::RN, dvector![5.0]));
365 (problem, init)
366 }
367
368 #[test]
373 fn test_linearize_block_residual_value() -> TestResult {
374 let (problem, init) = one_var_problem();
375 let state = optimizer::initialize_optimization_state(&problem, &init)?;
376 let total_residual = Arc::new(Mutex::new(Col::<f64>::zeros(1)));
377 let block = problem
378 .residual_blocks()
379 .values()
380 .next()
381 .ok_or("no residual blocks")?;
382 linearize_block(block, &state.variables, &total_residual)?;
383 let r = total_residual.lock().map_err(|e| format!("{e:?}"))?;
384 assert!((r[0] - 5.0).abs() < 1e-12);
385 Ok(())
386 }
387
388 #[test]
389 fn test_linearize_block_jacobian_shape() -> TestResult {
390 let (problem, init) = one_var_problem();
391 let state = optimizer::initialize_optimization_state(&problem, &init)?;
392 let total_residual = Arc::new(Mutex::new(Col::<f64>::zeros(1)));
393 let block = problem
394 .residual_blocks()
395 .values()
396 .next()
397 .ok_or("no residual blocks")?;
398 let result = linearize_block(block, &state.variables, &total_residual)?;
399 assert_eq!(result.jacobian.nrows(), 1);
400 assert_eq!(result.jacobian.ncols(), 1);
401 Ok(())
402 }
403
404 #[test]
405 fn test_linearize_block_variable_local_idx() -> TestResult {
406 let (problem, init) = one_var_problem();
407 let state = optimizer::initialize_optimization_state(&problem, &init)?;
408 let total_residual = Arc::new(Mutex::new(Col::<f64>::zeros(1)));
409 let block = problem
410 .residual_blocks()
411 .values()
412 .next()
413 .ok_or("no residual blocks")?;
414 let result = linearize_block(block, &state.variables, &total_residual)?;
415 assert_eq!(result.variable_local_idx_size_list.len(), 1);
416 let (local_idx, size) = result.variable_local_idx_size_list[0];
417 assert_eq!(local_idx, 0);
418 assert_eq!(size, 1);
419 Ok(())
420 }
421
422 #[test]
427 fn test_sparse_backend_assemble() -> TestResult {
428 let (problem, init) = one_var_problem();
429 let state = optimizer::initialize_optimization_state(&problem, &init)?;
430 let (residual, _) = SparseMode::assemble(
431 &problem,
432 &state.variables,
433 &state.variable_index_map,
434 state.symbolic_structure.as_ref(),
435 state.total_dof,
436 )?;
437 assert!((residual[(0, 0)] - 5.0).abs() < 1e-12);
438 Ok(())
439 }
440
441 #[test]
442 fn test_sparse_backend_assemble_no_symbolic_returns_error() -> TestResult {
443 let (problem, init) = one_var_problem();
444 let state = optimizer::initialize_optimization_state(&problem, &init)?;
445 let result = SparseMode::assemble(
446 &problem,
447 &state.variables,
448 &state.variable_index_map,
449 None, state.total_dof,
451 );
452 assert!(result.is_err());
453 Ok(())
454 }
455
456 #[test]
457 fn test_sparse_backend_compute_column_norms() -> TestResult {
458 let (problem, init) = one_var_problem();
459 let state = optimizer::initialize_optimization_state(&problem, &init)?;
460 let (_, jacobian) = SparseMode::assemble(
461 &problem,
462 &state.variables,
463 &state.variable_index_map,
464 state.symbolic_structure.as_ref(),
465 state.total_dof,
466 )?;
467 let norms = SparseMode::compute_column_norms(&jacobian);
468 assert_eq!(norms.len(), 1);
469 assert!((norms[0] - 1.0).abs() < 1e-12);
470 Ok(())
471 }
472
473 #[test]
474 fn test_sparse_backend_apply_column_scaling() -> TestResult {
475 let (problem, init) = one_var_problem();
476 let state = optimizer::initialize_optimization_state(&problem, &init)?;
477 let (_, jacobian) = SparseMode::assemble(
478 &problem,
479 &state.variables,
480 &state.variable_index_map,
481 state.symbolic_structure.as_ref(),
482 state.total_dof,
483 )?;
484 let scaling = vec![0.5_f64];
485 let scaled = SparseMode::apply_column_scaling(&jacobian, &scaling);
486 let val = scaled.as_ref().val_of_col(0)[0];
487 assert!((val - 0.5).abs() < 1e-12);
488 Ok(())
489 }
490
491 #[test]
492 fn test_sparse_backend_apply_inverse_scaling() {
493 let step = Mat::from_fn(1, 1, |_, _| 1.0_f64);
494 let scaling = vec![2.0_f64];
495 let result = SparseMode::apply_inverse_scaling(&step, &scaling);
496 assert!((result[(0, 0)] - 2.0).abs() < 1e-12);
497 }
498
499 #[test]
500 fn test_sparse_backend_hessian_vec_product() -> TestResult {
501 let triplets = vec![faer::sparse::Triplet::new(0usize, 0usize, 4.0_f64)];
502 let h = SparseColMat::try_new_from_triplets(1, 1, &triplets)?;
503 let v = Mat::from_fn(1, 1, |_, _| 2.0_f64);
504 let result = SparseMode::hessian_vec_product(&h, &v);
505 assert!((result[(0, 0)] - 8.0).abs() < 1e-12);
506 Ok(())
507 }
508
509 #[test]
514 fn test_dense_backend_assemble() -> TestResult {
515 let mut problem = Problem::new(JacobianMode::Dense);
516 problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 0.0 }), None);
517 let mut init = HashMap::new();
518 init.insert("x".to_string(), (ManifoldType::RN, dvector![5.0]));
519 let state = optimizer::initialize_optimization_state(&problem, &init)?;
520 let (residual, _) = DenseMode::assemble(
521 &problem,
522 &state.variables,
523 &state.variable_index_map,
524 None,
525 state.total_dof,
526 )?;
527 assert!((residual[(0, 0)] - 5.0).abs() < 1e-12);
528 Ok(())
529 }
530
531 #[test]
532 fn test_dense_backend_compute_column_norms() {
533 let jacobian = Mat::from_fn(1, 1, |_, _| 1.0_f64);
534 let norms = DenseMode::compute_column_norms(&jacobian);
535 assert_eq!(norms.len(), 1);
536 assert!((norms[0] - 1.0).abs() < 1e-12);
537 }
538
539 #[test]
540 fn test_dense_backend_apply_column_scaling() {
541 let jacobian = Mat::from_fn(1, 1, |_, _| 1.0_f64);
542 let scaling = vec![0.5_f64];
543 let scaled = DenseMode::apply_column_scaling(&jacobian, &scaling);
544 assert!((scaled[(0, 0)] - 0.5).abs() < 1e-12);
545 }
546
547 #[test]
548 fn test_dense_backend_apply_inverse_scaling() {
549 let step = Mat::from_fn(1, 1, |_, _| 1.0_f64);
550 let scaling = vec![2.0_f64];
551 let result = DenseMode::apply_inverse_scaling(&step, &scaling);
552 assert!((result[(0, 0)] - 2.0).abs() < 1e-12);
553 }
554
555 #[test]
556 fn test_dense_backend_hessian_vec_product() {
557 let h = Mat::from_fn(1, 1, |_, _| 4.0_f64);
558 let v = Mat::from_fn(1, 1, |_, _| 2.0_f64);
559 let result = DenseMode::hessian_vec_product(&h, &v);
560 assert!((result[(0, 0)] - 8.0).abs() < 1e-12);
561 }
562}