apex_solver/optimizer/gauss_newton.rs
1//! Gauss-Newton optimization algorithm implementation.
2//!
3//! The Gauss-Newton method is a fundamental iterative algorithm for solving nonlinear least squares problems
4//! of the form:
5//!
6//! ```text
7//! min f(x) = ½||r(x)||² = ½Σᵢ rᵢ(x)²
8//! ```
9//!
10//! where `r: ℝⁿ → ℝᵐ` is the residual vector function.
11//!
12//! # Algorithm Overview
13//!
14//! The Gauss-Newton method solves the normal equations at each iteration:
15//!
16//! ```text
17//! J^T·J·h = -J^T·r
18//! ```
19//!
20//! where:
21//! - `J` is the Jacobian matrix (m × n) of partial derivatives ∂rᵢ/∂xⱼ
22//! - `r` is the residual vector (m × 1)
23//! - `h` is the step vector (n × 1)
24//!
25//! The approximated Hessian `H ≈ J^T·J` replaces the true Hessian `∇²f = J^T·J + Σᵢ rᵢ·∇²rᵢ`,
26//! which works well when residuals are small or nearly linear.
27//!
28//! ## Convergence Properties
29//!
30//! - **Quadratic convergence** near the solution when the Gauss-Newton approximation is valid
31//! - **May diverge** if the initial guess is far from the optimum or the problem is ill-conditioned
32//! - **No step size control** - always takes the full Newton step without damping
33//!
34//! ## When to Use
35//!
36//! Gauss-Newton is most effective when:
37//! - The problem is well-conditioned with `J^T·J` having good numerical properties
38//! - The initial parameter guess is close to the solution
39//! - Fast convergence is prioritized over robustness
40//! - Residuals at the solution are expected to be small
41//!
42//! For ill-conditioned problems or poor initial guesses, consider:
43//! - [`LevenbergMarquardt`](crate::optimizer::LevenbergMarquardt) for adaptive damping
44//! - [`DogLeg`](crate::optimizer::DogLeg) for trust region control
45//!
46//! # Implementation Features
47//!
48//! - **Sparse matrix support**: Efficient handling of large-scale problems via `faer` sparse library
49//! - **Robust linear solvers**: Choice between Cholesky (fast) and QR (stable) factorizations
50//! - **Jacobi scaling**: Optional diagonal preconditioning to improve conditioning
51//! - **Manifold operations**: Support for optimization on Lie groups (SE2, SE3, SO2, SO3)
52//! - **Comprehensive diagnostics**: Detailed convergence and performance summaries
53//!
54//! # Mathematical Background
55//!
56//! At each iteration k, the algorithm:
57//!
58//! 1. **Linearizes** the problem around current estimate xₖ: `r(xₖ + h) ≈ r(xₖ) + J(xₖ)·h`
59//! 2. **Solves** the normal equations for step h: `J^T·J·h = -J^T·r`
60//! 3. **Updates** parameters: `xₖ₊₁ = xₖ ⊕ h` (using manifold plus operation)
61//! 4. **Checks** convergence criteria (cost, gradient, parameter change)
62//!
63//! The method terminates when cost change, gradient norm, or parameter update fall below
64//! specified tolerances, or when maximum iterations are reached.
65//!
66//! # Examples
67//!
68//! ## Basic usage
69//!
70//! ```no_run
71//! use apex_solver::optimizer::GaussNewton;
72//! use apex_solver::core::problem::Problem;
73//! use std::collections::HashMap;
74//!
75//! # fn main() -> Result<(), Box<dyn std::error::Error>> {
76//! // Create optimization problem
77//! let mut problem = Problem::new();
78//! // ... add residual blocks (factors) to problem ...
79//!
80//! // Set up initial parameter values
81//! let initial_values = HashMap::new();
82//! // ... initialize parameters ...
83//!
84//! // Create solver with default configuration
85//! let mut solver = GaussNewton::new();
86//!
87//! // Run optimization
88//! let result = solver.optimize(&problem, &initial_values)?;
89//! # Ok(())
90//! # }
91//! ```
92//!
93//! ## Advanced configuration
94//!
95//! ```no_run
96//! use apex_solver::optimizer::gauss_newton::{GaussNewtonConfig, GaussNewton};
97//! use apex_solver::linalg::LinearSolverType;
98//!
99//! # fn main() {
100//! let config = GaussNewtonConfig::new()
101//! .with_max_iterations(100)
102//! .with_cost_tolerance(1e-8)
103//! .with_parameter_tolerance(1e-8)
104//! .with_gradient_tolerance(1e-10)
105//! .with_linear_solver_type(LinearSolverType::SparseQR) // More stable
106//! .with_jacobi_scaling(true); // Improve conditioning
107//!
108//! let mut solver = GaussNewton::with_config(config);
109//! # }
110//! ```
111//!
112//! # References
113//!
114//! - Nocedal, J. & Wright, S. (2006). *Numerical Optimization* (2nd ed.). Springer. Chapter 10.
115//! - Madsen, K., Nielsen, H. B., & Tingleff, O. (2004). *Methods for Non-Linear Least Squares Problems* (2nd ed.).
116//! - Björck, Å. (1996). *Numerical Methods for Least Squares Problems*. SIAM.
117
118use crate::{core::problem, error, linalg, optimizer};
119use apex_manifolds as manifold;
120
121use faer::sparse;
122use std::{collections, time};
123use tracing::debug;
124
125use crate::optimizer::IterationStats;
126
127/// Configuration parameters for the Gauss-Newton optimizer.
128///
129/// Controls the behavior of the Gauss-Newton algorithm including convergence criteria,
130/// linear solver selection, and numerical stability enhancements.
131///
132/// # Builder Pattern
133///
134/// All configuration options can be set using the builder pattern:
135///
136/// ```
137/// use apex_solver::optimizer::gauss_newton::GaussNewtonConfig;
138/// use apex_solver::linalg::LinearSolverType;
139///
140/// let config = GaussNewtonConfig::new()
141/// .with_max_iterations(50)
142/// .with_cost_tolerance(1e-6)
143/// .with_linear_solver_type(LinearSolverType::SparseQR);
144/// ```
145///
146/// # Convergence Criteria
147///
148/// The optimizer terminates when ANY of the following conditions is met:
149///
150/// - **Cost tolerance**: `|cost_k - cost_{k-1}| < cost_tolerance`
151/// - **Parameter tolerance**: `||step|| < parameter_tolerance`
152/// - **Gradient tolerance**: `||J^T·r|| < gradient_tolerance`
153/// - **Maximum iterations**: `iteration >= max_iterations`
154/// - **Timeout**: `elapsed_time >= timeout`
155///
156/// # See Also
157///
158/// - [`GaussNewton`] - The solver that uses this configuration
159/// - [`LevenbergMarquardtConfig`](crate::optimizer::LevenbergMarquardtConfig) - For adaptive damping
160/// - [`DogLegConfig`](crate::optimizer::DogLegConfig) - For trust region methods
161#[derive(Clone)]
162pub struct GaussNewtonConfig {
163 /// Type of linear solver for the linear systems
164 pub linear_solver_type: linalg::LinearSolverType,
165 /// Maximum number of iterations
166 pub max_iterations: usize,
167 /// Convergence tolerance for cost function
168 pub cost_tolerance: f64,
169 /// Convergence tolerance for parameter updates
170 pub parameter_tolerance: f64,
171 /// Convergence tolerance for gradient norm
172 pub gradient_tolerance: f64,
173 /// Timeout duration
174 pub timeout: Option<time::Duration>,
175 /// Use Jacobi column scaling (preconditioning)
176 ///
177 /// When enabled, normalizes Jacobian columns by their L2 norm before solving.
178 /// This can improve convergence for problems with mixed parameter scales
179 /// (e.g., positions in meters + angles in radians) but adds ~5-10% overhead.
180 ///
181 /// Default: false (Gauss-Newton is typically used on well-conditioned problems)
182 pub use_jacobi_scaling: bool,
183 /// Small regularization to ensure J^T·J is positive definite
184 ///
185 /// Pure Gauss-Newton (λ=0) can fail when J^T·J is singular or near-singular.
186 /// Adding a tiny diagonal regularization (e.g., 1e-10) ensures numerical stability
187 /// while maintaining the fast convergence of Gauss-Newton.
188 ///
189 /// Default: 1e-10 (very small, practically identical to pure Gauss-Newton)
190 pub min_diagonal: f64,
191
192 /// Minimum objective function cutoff (optional early termination)
193 ///
194 /// If set, optimization terminates when cost falls below this threshold.
195 /// Useful for early stopping when a "good enough" solution is acceptable.
196 ///
197 /// Default: None (disabled)
198 pub min_cost_threshold: Option<f64>,
199
200 /// Maximum condition number for Jacobian matrix (optional check)
201 ///
202 /// If set, the optimizer checks if condition_number(J^T*J) exceeds this
203 /// threshold and terminates with IllConditionedJacobian status.
204 /// Note: Computing condition number is expensive, so this is disabled by default.
205 ///
206 /// Default: None (disabled)
207 pub max_condition_number: Option<f64>,
208
209 /// Compute per-variable covariance matrices (uncertainty estimation)
210 ///
211 /// When enabled, computes covariance by inverting the Hessian matrix after
212 /// convergence. The full covariance matrix is extracted into per-variable
213 /// blocks stored in both Variable structs and optimier::SolverResult.
214 ///
215 /// Default: false (to avoid performance overhead)
216 pub compute_covariances: bool,
217
218 /// Enable real-time visualization (graphical debugging).
219 ///
220 /// When enabled, optimization progress is logged to a Rerun viewer.
221 /// **Note:** Requires the `visualization` feature to be enabled in `Cargo.toml`.
222 ///
223 /// Default: false
224 #[cfg(feature = "visualization")]
225 pub enable_visualization: bool,
226}
227
228impl Default for GaussNewtonConfig {
229 fn default() -> Self {
230 Self {
231 linear_solver_type: linalg::LinearSolverType::default(),
232 // Ceres Solver default: 50 (changed from 100 for compatibility)
233 max_iterations: 50,
234 // Ceres Solver default: 1e-6 (changed from 1e-8 for compatibility)
235 cost_tolerance: 1e-6,
236 // Ceres Solver default: 1e-8 (unchanged)
237 parameter_tolerance: 1e-8,
238 // Ceres Solver default: 1e-10 (changed from 1e-8 for compatibility)
239 gradient_tolerance: 1e-10,
240 timeout: None,
241 use_jacobi_scaling: false,
242 min_diagonal: 1e-10,
243 // New Ceres-compatible termination parameters
244 min_cost_threshold: None,
245 max_condition_number: None,
246 compute_covariances: false,
247 #[cfg(feature = "visualization")]
248 enable_visualization: false,
249 }
250 }
251}
252
253impl GaussNewtonConfig {
254 /// Create a new Gauss-Newton configuration with default values.
255 pub fn new() -> Self {
256 Self::default()
257 }
258
259 /// Set the linear solver type
260 pub fn with_linear_solver_type(mut self, linear_solver_type: linalg::LinearSolverType) -> Self {
261 self.linear_solver_type = linear_solver_type;
262 self
263 }
264
265 /// Set the maximum number of iterations
266 pub fn with_max_iterations(mut self, max_iterations: usize) -> Self {
267 self.max_iterations = max_iterations;
268 self
269 }
270
271 /// Set the cost tolerance
272 pub fn with_cost_tolerance(mut self, cost_tolerance: f64) -> Self {
273 self.cost_tolerance = cost_tolerance;
274 self
275 }
276
277 /// Set the parameter tolerance
278 pub fn with_parameter_tolerance(mut self, parameter_tolerance: f64) -> Self {
279 self.parameter_tolerance = parameter_tolerance;
280 self
281 }
282
283 /// Set the gradient tolerance
284 pub fn with_gradient_tolerance(mut self, gradient_tolerance: f64) -> Self {
285 self.gradient_tolerance = gradient_tolerance;
286 self
287 }
288
289 /// Set the timeout duration
290 pub fn with_timeout(mut self, timeout: time::Duration) -> Self {
291 self.timeout = Some(timeout);
292 self
293 }
294
295 /// Enable or disable Jacobi column scaling (preconditioning).
296 ///
297 /// When enabled, normalizes Jacobian columns by their L2 norm before solving.
298 /// Can improve convergence for mixed-scale problems but adds ~5-10% overhead.
299 pub fn with_jacobi_scaling(mut self, use_jacobi_scaling: bool) -> Self {
300 self.use_jacobi_scaling = use_jacobi_scaling;
301 self
302 }
303
304 /// Set the minimum diagonal regularization for numerical stability.
305 ///
306 /// A small value (e.g., 1e-10) ensures J^T·J is positive definite while
307 /// maintaining the fast convergence of pure Gauss-Newton.
308 pub fn with_min_diagonal(mut self, min_diagonal: f64) -> Self {
309 self.min_diagonal = min_diagonal;
310 self
311 }
312
313 /// Set minimum objective function cutoff for early termination.
314 ///
315 /// When set, optimization terminates with MinCostThresholdReached status
316 /// if the cost falls below this threshold. Useful for early stopping when
317 /// a "good enough" solution is acceptable.
318 pub fn with_min_cost_threshold(mut self, min_cost: f64) -> Self {
319 self.min_cost_threshold = Some(min_cost);
320 self
321 }
322
323 /// Set maximum condition number for Jacobian matrix.
324 ///
325 /// If set, the optimizer checks if condition_number(J^T*J) exceeds this
326 /// threshold and terminates with IllConditionedJacobian status.
327 /// Note: Computing condition number is expensive, disabled by default.
328 pub fn with_max_condition_number(mut self, max_cond: f64) -> Self {
329 self.max_condition_number = Some(max_cond);
330 self
331 }
332
333 /// Enable or disable covariance computation (uncertainty estimation).
334 ///
335 /// When enabled, computes the full covariance matrix by inverting the Hessian
336 /// after convergence, then extracts per-variable covariance blocks.
337 pub fn with_compute_covariances(mut self, compute_covariances: bool) -> Self {
338 self.compute_covariances = compute_covariances;
339 self
340 }
341
342 /// Enable real-time visualization.
343 ///
344 /// **Note:** Requires the `visualization` feature to be enabled in `Cargo.toml`.
345 ///
346 /// # Arguments
347 ///
348 /// * `enable` - Whether to enable visualization
349 #[cfg(feature = "visualization")]
350 pub fn with_visualization(mut self, enable: bool) -> Self {
351 self.enable_visualization = enable;
352 self
353 }
354
355 /// Print configuration parameters (info level logging)
356 pub fn print_configuration(&self) {
357 debug!(
358 "\nConfiguration:\n Solver: Gauss-Newton\n Linear solver: {:?}\n Convergence Criteria:\n Max iterations: {}\n Cost tolerance: {:.2e}\n Parameter tolerance: {:.2e}\n Gradient tolerance: {:.2e}\n Timeout: {:?}\n Numerical Settings:\n Jacobi scaling: {}\n Compute covariances: {}",
359 self.linear_solver_type,
360 self.max_iterations,
361 self.cost_tolerance,
362 self.parameter_tolerance,
363 self.gradient_tolerance,
364 self.timeout,
365 if self.use_jacobi_scaling {
366 "enabled"
367 } else {
368 "disabled"
369 },
370 if self.compute_covariances {
371 "enabled"
372 } else {
373 "disabled"
374 }
375 );
376 }
377}
378
379/// Result from step computation
380struct StepResult {
381 step: faer::Mat<f64>,
382 gradient_norm: f64,
383}
384
385/// Result from cost evaluation
386struct CostEvaluation {
387 new_cost: f64,
388 cost_reduction: f64,
389}
390
391/// Gauss-Newton solver for nonlinear least squares optimization.
392///
393/// Implements the classical Gauss-Newton algorithm which solves `J^T·J·h = -J^T·r` at each
394/// iteration to find the step `h`. This provides fast quadratic convergence near the solution
395/// but may diverge for poor initial guesses or ill-conditioned problems.
396///
397/// # Algorithm
398///
399/// At each iteration k:
400/// 1. Compute residual `r(xₖ)` and Jacobian `J(xₖ)`
401/// 2. Form normal equations: `(J^T·J)·h = -J^T·r`
402/// 3. Solve for step `h` using Cholesky or QR factorization
403/// 4. Update parameters: `xₖ₊₁ = xₖ ⊕ h` (manifold plus operation)
404/// 5. Check convergence criteria
405///
406/// # Examples
407///
408/// ```no_run
409/// use apex_solver::optimizer::GaussNewton;
410/// use apex_solver::core::problem::Problem;
411/// use std::collections::HashMap;
412///
413/// # fn main() -> Result<(), Box<dyn std::error::Error>> {
414/// let mut problem = Problem::new();
415/// // ... add factors to problem ...
416///
417/// let initial_values = HashMap::new();
418/// // ... initialize parameters ...
419///
420/// let mut solver = GaussNewton::new();
421/// let result = solver.optimize(&problem, &initial_values)?;
422/// # Ok(())
423/// # }
424/// ```
425///
426/// # See Also
427///
428/// - [`GaussNewtonConfig`] - Configuration options
429/// - [`LevenbergMarquardt`](crate::optimizer::LevenbergMarquardt) - For adaptive damping
430/// - [`DogLeg`](crate::optimizer::DogLeg) - For trust region control
431pub struct GaussNewton {
432 config: GaussNewtonConfig,
433 jacobi_scaling: Option<sparse::SparseColMat<usize, f64>>,
434 observers: optimizer::OptObserverVec,
435}
436
437impl Default for GaussNewton {
438 fn default() -> Self {
439 Self::new()
440 }
441}
442
443impl GaussNewton {
444 /// Create a new Gauss-Newton solver with default configuration.
445 pub fn new() -> Self {
446 Self::with_config(GaussNewtonConfig::default())
447 }
448
449 /// Create a new Gauss-Newton solver with the given configuration.
450 pub fn with_config(config: GaussNewtonConfig) -> Self {
451 Self {
452 config,
453 jacobi_scaling: None,
454 observers: optimizer::OptObserverVec::new(),
455 }
456 }
457
458 /// Add an observer to the solver.
459 ///
460 /// Observers are notified at each iteration with the current variable values.
461 /// This enables real-time visualization, logging, metrics collection, etc.
462 ///
463 /// # Examples
464 ///
465 /// ```no_run
466 /// use apex_solver::optimizer::GaussNewton;
467 /// # use apex_solver::optimizer::OptObserver;
468 /// # use std::collections::HashMap;
469 /// # use apex_solver::core::problem::VariableEnum;
470 ///
471 /// # struct MyObserver;
472 /// # impl OptObserver for MyObserver {
473 /// # fn on_step(&self, _: &HashMap<String, VariableEnum>, _: usize) {}
474 /// # }
475 /// let mut solver = GaussNewton::new();
476 /// solver.add_observer(MyObserver);
477 /// ```
478 pub fn add_observer(&mut self, observer: impl optimizer::OptObserver + 'static) {
479 self.observers.add(observer);
480 }
481
482 /// Compute Gauss-Newton step by solving the normal equations
483 fn compute_gauss_newton_step(
484 &self,
485 residuals: &faer::Mat<f64>,
486 scaled_jacobian: &sparse::SparseColMat<usize, f64>,
487 linear_solver: &mut Box<dyn linalg::SparseLinearSolver>,
488 ) -> Option<StepResult> {
489 // Solve the Gauss-Newton equation: J^T·J·Δx = -J^T·r
490 // Use min_diagonal for numerical stability (tiny regularization)
491 let residuals_owned = residuals.as_ref().to_owned();
492 let scaled_step = linear_solver
493 .solve_normal_equation(&residuals_owned, scaled_jacobian)
494 .ok()?;
495
496 // Get gradient from the solver (J^T * r)
497 let gradient = linear_solver.get_gradient()?;
498 // Compute gradient norm for convergence check
499 let gradient_norm = gradient.norm_l2();
500
501 // Apply inverse Jacobi scaling to get final step (if enabled)
502 let step = if self.config.use_jacobi_scaling {
503 let scaling = self.jacobi_scaling.as_ref()?;
504 &scaled_step * scaling
505 } else {
506 scaled_step
507 };
508
509 Some(StepResult {
510 step,
511 gradient_norm,
512 })
513 }
514
515 /// Apply step to parameters and evaluate new cost
516 fn apply_step_and_evaluate_cost(
517 &self,
518 step_result: &StepResult,
519 state: &mut optimizer::InitializedState,
520 problem: &problem::Problem,
521 ) -> error::ApexSolverResult<CostEvaluation> {
522 // Apply parameter updates using manifold operations
523 let _step_norm = optimizer::apply_parameter_step(
524 &mut state.variables,
525 step_result.step.as_ref(),
526 &state.sorted_vars,
527 );
528
529 // Compute new cost (residual only, no Jacobian needed for step evaluation)
530 let new_residual = problem.compute_residual_sparse(&state.variables)?;
531 let new_cost = optimizer::compute_cost(&new_residual);
532
533 // Compute cost reduction
534 let cost_reduction = state.current_cost - new_cost;
535
536 // Update current cost
537 state.current_cost = new_cost;
538
539 Ok(CostEvaluation {
540 new_cost,
541 cost_reduction,
542 })
543 }
544
545 pub fn optimize(
546 &mut self,
547 problem: &problem::Problem,
548 initial_params: &collections::HashMap<
549 String,
550 (manifold::ManifoldType, nalgebra::DVector<f64>),
551 >,
552 ) -> Result<
553 optimizer::SolverResult<collections::HashMap<String, problem::VariableEnum>>,
554 error::ApexSolverError,
555 > {
556 let start_time = time::Instant::now();
557 let mut iteration = 0;
558 let mut cost_evaluations = 1; // Initial cost evaluation
559 let mut jacobian_evaluations = 0;
560
561 // Initialize optimization state
562 let mut state = optimizer::initialize_optimization_state(problem, initial_params)?;
563
564 // Create linear solver
565 let mut linear_solver = optimizer::create_linear_solver(&self.config.linear_solver_type);
566
567 // Initialize summary tracking variables
568 let mut max_gradient_norm: f64 = 0.0;
569 let mut max_parameter_update_norm: f64 = 0.0;
570 let mut total_cost_reduction = 0.0;
571 let mut final_gradient_norm;
572 let mut final_parameter_update_norm;
573
574 // Initialize iteration statistics tracking
575 let mut iteration_stats = Vec::with_capacity(self.config.max_iterations);
576 let mut previous_cost = state.current_cost;
577
578 // Print configuration and header if debug level is enabled
579 if tracing::enabled!(tracing::Level::DEBUG) {
580 self.config.print_configuration();
581 IterationStats::print_header();
582 }
583
584 // Main optimization loop
585 loop {
586 let iter_start = time::Instant::now();
587 // Evaluate residuals and Jacobian
588 let (residuals, jacobian) = problem.compute_residual_and_jacobian_sparse(
589 &state.variables,
590 &state.variable_index_map,
591 &state.symbolic_structure,
592 )?;
593 jacobian_evaluations += 1;
594
595 // Process Jacobian (apply scaling if enabled)
596 let scaled_jacobian = if self.config.use_jacobi_scaling {
597 optimizer::process_jacobian(&jacobian, &mut self.jacobi_scaling, iteration)?
598 } else {
599 jacobian
600 };
601
602 // Compute Gauss-Newton step
603 let step_result = match self.compute_gauss_newton_step(
604 &residuals,
605 &scaled_jacobian,
606 &mut linear_solver,
607 ) {
608 Some(result) => result,
609 None => {
610 return Err(optimizer::OptimizerError::LinearSolveFailed(
611 "Linear solver failed to solve Gauss-Newton system".to_string(),
612 )
613 .into());
614 }
615 };
616
617 // Update tracking variables
618 max_gradient_norm = max_gradient_norm.max(step_result.gradient_norm);
619 final_gradient_norm = step_result.gradient_norm;
620 let step_norm = step_result.step.norm_l2();
621 max_parameter_update_norm = max_parameter_update_norm.max(step_norm);
622 final_parameter_update_norm = step_norm;
623
624 // Capture cost before applying step (for convergence check)
625 let cost_before_step = state.current_cost;
626
627 // Apply step and evaluate new cost
628 let cost_eval = self.apply_step_and_evaluate_cost(&step_result, &mut state, problem)?;
629 cost_evaluations += 1;
630 total_cost_reduction += cost_eval.cost_reduction;
631
632 // OPTIMIZATION: Only collect iteration statistics if debug level is enabled
633 // This eliminates ~2-5ms overhead per iteration for non-debug optimization
634 if tracing::enabled!(tracing::Level::DEBUG) {
635 let iter_elapsed_ms = iter_start.elapsed().as_secs_f64() * 1000.0;
636 let total_elapsed_ms = start_time.elapsed().as_secs_f64() * 1000.0;
637
638 let stats = IterationStats {
639 iteration,
640 cost: state.current_cost,
641 cost_change: previous_cost - state.current_cost,
642 gradient_norm: step_result.gradient_norm,
643 step_norm,
644 tr_ratio: 0.0, // Not used in Gauss-Newton
645 tr_radius: 0.0, // Not used in Gauss-Newton
646 ls_iter: 0, // Direct solver (Cholesky) has no iterations
647 iter_time_ms: iter_elapsed_ms,
648 total_time_ms: total_elapsed_ms,
649 accepted: true, // Gauss-Newton always accepts steps
650 };
651
652 iteration_stats.push(stats.clone());
653 stats.print_line();
654 }
655
656 previous_cost = state.current_cost;
657
658 // Notify all observers with current state
659 optimizer::notify_observers(
660 &mut self.observers,
661 &state.variables,
662 iteration,
663 state.current_cost,
664 step_result.gradient_norm,
665 None, // Gauss-Newton doesn't use damping
666 step_norm,
667 None, // Gauss-Newton doesn't use step quality
668 linear_solver.as_ref(),
669 );
670
671 // Compute parameter norm for convergence check
672 let parameter_norm = optimizer::compute_parameter_norm(&state.variables);
673
674 // Check convergence using comprehensive termination criteria
675 let elapsed = start_time.elapsed();
676 if let Some(status) = optimizer::check_convergence(&optimizer::ConvergenceParams {
677 iteration,
678 current_cost: cost_before_step,
679 new_cost: cost_eval.new_cost,
680 parameter_norm,
681 parameter_update_norm: step_norm,
682 gradient_norm: step_result.gradient_norm,
683 elapsed,
684 step_accepted: true, // GN always accepts
685 max_iterations: self.config.max_iterations,
686 gradient_tolerance: self.config.gradient_tolerance,
687 parameter_tolerance: self.config.parameter_tolerance,
688 cost_tolerance: self.config.cost_tolerance,
689 min_cost_threshold: self.config.min_cost_threshold,
690 timeout: self.config.timeout,
691 trust_region_radius: None,
692 min_trust_region_radius: None,
693 }) {
694 // Print summary only if debug level is enabled
695 if tracing::enabled!(tracing::Level::DEBUG) {
696 let summary = optimizer::create_optimizer_summary(
697 "Gauss-Newton",
698 state.initial_cost,
699 state.current_cost,
700 iteration + 1,
701 None,
702 None,
703 max_gradient_norm,
704 final_gradient_norm,
705 max_parameter_update_norm,
706 final_parameter_update_norm,
707 total_cost_reduction,
708 elapsed,
709 iteration_stats.clone(),
710 status.clone(),
711 None,
712 None,
713 None,
714 );
715 debug!("{}", summary);
716 }
717
718 // Compute covariances if enabled
719 let covariances = if self.config.compute_covariances {
720 problem.compute_and_set_covariances(
721 &mut linear_solver,
722 &mut state.variables,
723 &state.variable_index_map,
724 )
725 } else {
726 None
727 };
728
729 return Ok(optimizer::build_solver_result(
730 status,
731 iteration + 1,
732 state,
733 elapsed,
734 final_gradient_norm,
735 final_parameter_update_norm,
736 cost_evaluations,
737 jacobian_evaluations,
738 covariances,
739 ));
740 }
741
742 iteration += 1;
743 }
744 }
745}
746
747impl optimizer::Solver for GaussNewton {
748 type Config = GaussNewtonConfig;
749 type Error = error::ApexSolverError;
750
751 fn new() -> Self {
752 Self::default()
753 }
754
755 fn optimize(
756 &mut self,
757 problem: &problem::Problem,
758 initial_params: &std::collections::HashMap<
759 String,
760 (manifold::ManifoldType, nalgebra::DVector<f64>),
761 >,
762 ) -> Result<
763 optimizer::SolverResult<std::collections::HashMap<String, problem::VariableEnum>>,
764 Self::Error,
765 > {
766 self.optimize(problem, initial_params)
767 }
768}
769
770#[cfg(test)]
771mod tests {
772 use crate::{core::problem, factors, optimizer};
773 use apex_manifolds as manifold;
774 use nalgebra::dvector;
775 use std::collections;
776
777 /// Custom Rosenbrock Factor 1: r1 = 10(x2 - x1²)
778 /// Demonstrates extensibility - custom factors can be defined outside of factors.rs
779 #[derive(Debug, Clone)]
780 struct RosenbrockFactor1;
781
782 impl factors::Factor for RosenbrockFactor1 {
783 fn linearize(
784 &self,
785 params: &[nalgebra::DVector<f64>],
786 compute_jacobian: bool,
787 ) -> (nalgebra::DVector<f64>, Option<nalgebra::DMatrix<f64>>) {
788 let x1 = params[0][0];
789 let x2 = params[1][0];
790
791 // Residual: r1 = 10(x2 - x1²)
792 let residual = nalgebra::dvector![10.0 * (x2 - x1 * x1)];
793
794 // Jacobian: ∂r1/∂x1 = -20*x1, ∂r1/∂x2 = 10
795 let jacobian = if compute_jacobian {
796 let mut jac = nalgebra::DMatrix::zeros(1, 2);
797 jac[(0, 0)] = -20.0 * x1;
798 jac[(0, 1)] = 10.0;
799 Some(jac)
800 } else {
801 None
802 };
803
804 (residual, jacobian)
805 }
806
807 fn get_dimension(&self) -> usize {
808 1
809 }
810 }
811
812 /// Custom Rosenbrock Factor 2: r2 = 1 - x1
813 /// Demonstrates extensibility - custom factors can be defined outside of factors.rs
814 #[derive(Debug, Clone)]
815 struct RosenbrockFactor2;
816
817 impl factors::Factor for RosenbrockFactor2 {
818 fn linearize(
819 &self,
820 params: &[nalgebra::DVector<f64>],
821 compute_jacobian: bool,
822 ) -> (nalgebra::DVector<f64>, Option<nalgebra::DMatrix<f64>>) {
823 let x1 = params[0][0];
824
825 // Residual: r2 = 1 - x1
826 let residual = nalgebra::dvector![1.0 - x1];
827
828 // Jacobian: ∂r2/∂x1 = -1
829 let jacobian = if compute_jacobian {
830 Some(nalgebra::DMatrix::from_element(1, 1, -1.0))
831 } else {
832 None
833 };
834
835 (residual, jacobian)
836 }
837
838 fn get_dimension(&self) -> usize {
839 1
840 }
841 }
842
843 #[test]
844 fn test_rosenbrock_optimization() -> Result<(), Box<dyn std::error::Error>> {
845 // Rosenbrock function test:
846 // Minimize: r1² + r2² where
847 // r1 = 10(x2 - x1²)
848 // r2 = 1 - x1
849 // Starting point: [-1.2, 1.0]
850 // Expected minimum: [1.0, 1.0]
851
852 let mut problem = problem::Problem::new();
853 let mut initial_values = collections::HashMap::new();
854
855 // Add variables using Rn manifold (Euclidean space)
856 initial_values.insert(
857 "x1".to_string(),
858 (manifold::ManifoldType::RN, dvector![-1.2]),
859 );
860 initial_values.insert(
861 "x2".to_string(),
862 (manifold::ManifoldType::RN, dvector![1.0]),
863 );
864
865 // Add custom factors (demonstrates extensibility!)
866 problem.add_residual_block(&["x1", "x2"], Box::new(RosenbrockFactor1), None);
867 problem.add_residual_block(&["x1"], Box::new(RosenbrockFactor2), None);
868
869 // Configure Gauss-Newton optimizer
870 let config = optimizer::gauss_newton::GaussNewtonConfig::new()
871 .with_max_iterations(100)
872 .with_cost_tolerance(1e-8)
873 .with_parameter_tolerance(1e-8)
874 .with_gradient_tolerance(1e-10);
875
876 let mut solver = optimizer::GaussNewton::with_config(config);
877 let result = solver.optimize(&problem, &initial_values)?;
878
879 // Extract final values
880 let x1_final = result
881 .parameters
882 .get("x1")
883 .ok_or("x1 not found")?
884 .to_vector()[0];
885 let x2_final = result
886 .parameters
887 .get("x2")
888 .ok_or("x2 not found")?
889 .to_vector()[0];
890
891 // Verify convergence to [1.0, 1.0]
892 assert!(
893 matches!(
894 result.status,
895 optimizer::OptimizationStatus::Converged
896 | optimizer::OptimizationStatus::CostToleranceReached
897 | optimizer::OptimizationStatus::ParameterToleranceReached
898 | optimizer::OptimizationStatus::GradientToleranceReached
899 ),
900 "Optimization should converge"
901 );
902 assert!(
903 (x1_final - 1.0).abs() < 1e-4,
904 "x1 should converge to 1.0, got {}",
905 x1_final
906 );
907 assert!(
908 (x2_final - 1.0).abs() < 1e-4,
909 "x2 should converge to 1.0, got {}",
910 x2_final
911 );
912 assert!(
913 result.final_cost < 1e-6,
914 "Final cost should be near zero, got {}",
915 result.final_cost
916 );
917 Ok(())
918 }
919}