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//!
90//! println!("Converged: {:?}", result.status);
91//! println!("Final cost: {:.6e}", result.final_cost);
92//! println!("Iterations: {}", result.iterations);
93//! # Ok(())
94//! # }
95//! ```
96//!
97//! ## Advanced configuration
98//!
99//! ```no_run
100//! use apex_solver::optimizer::gauss_newton::{GaussNewtonConfig, GaussNewton};
101//! use apex_solver::linalg::LinearSolverType;
102//!
103//! # fn main() {
104//! let config = GaussNewtonConfig::new()
105//!     .with_max_iterations(100)
106//!     .with_cost_tolerance(1e-8)
107//!     .with_parameter_tolerance(1e-8)
108//!     .with_gradient_tolerance(1e-10)
109//!     .with_linear_solver_type(LinearSolverType::SparseQR)  // More stable
110//!     .with_jacobi_scaling(true)  // Improve conditioning
111//!     .with_verbose(true);
112//!
113//! let mut solver = GaussNewton::with_config(config);
114//! # }
115//! ```
116//!
117//! # References
118//!
119//! - Nocedal, J. & Wright, S. (2006). *Numerical Optimization* (2nd ed.). Springer. Chapter 10.
120//! - Madsen, K., Nielsen, H. B., & Tingleff, O. (2004). *Methods for Non-Linear Least Squares Problems* (2nd ed.).
121//! - Björck, Å. (1996). *Numerical Methods for Least Squares Problems*. SIAM.
122
123use crate::{core::problem, error, linalg, manifold, optimizer};
124use faer::sparse;
125use std::{collections, fmt, time};
126
127/// Summary statistics for the Gauss-Newton optimization process.
128#[derive(Debug, Clone)]
129pub struct GaussNewtonSummary {
130    /// Initial cost value
131    pub initial_cost: f64,
132    /// Final cost value
133    pub final_cost: f64,
134    /// Total number of iterations performed
135    pub iterations: usize,
136    /// Average cost reduction per iteration
137    pub average_cost_reduction: f64,
138    /// Maximum gradient norm encountered
139    pub max_gradient_norm: f64,
140    /// Final gradient norm
141    pub final_gradient_norm: f64,
142    /// Maximum parameter update norm
143    pub max_parameter_update_norm: f64,
144    /// Final parameter update norm
145    pub final_parameter_update_norm: f64,
146    /// Total time elapsed
147    pub total_time: time::Duration,
148    /// Average time per iteration
149    pub average_time_per_iteration: time::Duration,
150}
151
152impl fmt::Display for GaussNewtonSummary {
153    fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
154        writeln!(f, "=== Gauss-Newton Optimization Summary ===")?;
155        writeln!(f, "Initial cost:              {:.6e}", self.initial_cost)?;
156        writeln!(f, "Final cost:                {:.6e}", self.final_cost)?;
157        writeln!(
158            f,
159            "Cost reduction:            {:.6e} ({:.2}%)",
160            self.initial_cost - self.final_cost,
161            100.0 * (self.initial_cost - self.final_cost) / self.initial_cost.max(1e-12)
162        )?;
163        writeln!(f, "Total iterations:          {}", self.iterations)?;
164        writeln!(
165            f,
166            "Average cost reduction:    {:.6e}",
167            self.average_cost_reduction
168        )?;
169        writeln!(
170            f,
171            "Max gradient norm:         {:.6e}",
172            self.max_gradient_norm
173        )?;
174        writeln!(
175            f,
176            "Final gradient norm:       {:.6e}",
177            self.final_gradient_norm
178        )?;
179        writeln!(
180            f,
181            "Max parameter update norm: {:.6e}",
182            self.max_parameter_update_norm
183        )?;
184        writeln!(
185            f,
186            "Final param update norm:   {:.6e}",
187            self.final_parameter_update_norm
188        )?;
189        writeln!(f, "Total time:                {:?}", self.total_time)?;
190        writeln!(
191            f,
192            "Average time per iteration: {:?}",
193            self.average_time_per_iteration
194        )?;
195        Ok(())
196    }
197}
198
199/// Configuration parameters for the Gauss-Newton optimizer.
200///
201/// Controls the behavior of the Gauss-Newton algorithm including convergence criteria,
202/// linear solver selection, and numerical stability enhancements.
203///
204/// # Builder Pattern
205///
206/// All configuration options can be set using the builder pattern:
207///
208/// ```
209/// use apex_solver::optimizer::gauss_newton::GaussNewtonConfig;
210/// use apex_solver::linalg::LinearSolverType;
211///
212/// let config = GaussNewtonConfig::new()
213///     .with_max_iterations(50)
214///     .with_cost_tolerance(1e-6)
215///     .with_linear_solver_type(LinearSolverType::SparseQR)
216///     .with_verbose(true);
217/// ```
218///
219/// # Convergence Criteria
220///
221/// The optimizer terminates when ANY of the following conditions is met:
222///
223/// - **Cost tolerance**: `|cost_k - cost_{k-1}| < cost_tolerance`
224/// - **Parameter tolerance**: `||step|| < parameter_tolerance`
225/// - **Gradient tolerance**: `||J^T·r|| < gradient_tolerance`
226/// - **Maximum iterations**: `iteration >= max_iterations`
227/// - **Timeout**: `elapsed_time >= timeout`
228///
229/// # See Also
230///
231/// - [`GaussNewton`] - The solver that uses this configuration
232/// - [`LevenbergMarquardtConfig`](crate::optimizer::LevenbergMarquardtConfig) - For adaptive damping
233/// - [`DogLegConfig`](crate::optimizer::DogLegConfig) - For trust region methods
234#[derive(Clone)]
235pub struct GaussNewtonConfig {
236    /// Type of linear solver for the linear systems
237    pub linear_solver_type: linalg::LinearSolverType,
238    /// Maximum number of iterations
239    pub max_iterations: usize,
240    /// Convergence tolerance for cost function
241    pub cost_tolerance: f64,
242    /// Convergence tolerance for parameter updates
243    pub parameter_tolerance: f64,
244    /// Convergence tolerance for gradient norm
245    pub gradient_tolerance: f64,
246    /// Timeout duration
247    pub timeout: Option<time::Duration>,
248    /// Enable detailed logging
249    pub verbose: bool,
250    /// Use Jacobi column scaling (preconditioning)
251    ///
252    /// When enabled, normalizes Jacobian columns by their L2 norm before solving.
253    /// This can improve convergence for problems with mixed parameter scales
254    /// (e.g., positions in meters + angles in radians) but adds ~5-10% overhead.
255    ///
256    /// Default: false (Gauss-Newton is typically used on well-conditioned problems)
257    pub use_jacobi_scaling: bool,
258    /// Small regularization to ensure J^T·J is positive definite
259    ///
260    /// Pure Gauss-Newton (λ=0) can fail when J^T·J is singular or near-singular.
261    /// Adding a tiny diagonal regularization (e.g., 1e-10) ensures numerical stability
262    /// while maintaining the fast convergence of Gauss-Newton.
263    ///
264    /// Default: 1e-10 (very small, practically identical to pure Gauss-Newton)
265    pub min_diagonal: f64,
266
267    /// Minimum objective function cutoff (optional early termination)
268    ///
269    /// If set, optimization terminates when cost falls below this threshold.
270    /// Useful for early stopping when a "good enough" solution is acceptable.
271    ///
272    /// Default: None (disabled)
273    pub min_cost_threshold: Option<f64>,
274
275    /// Maximum condition number for Jacobian matrix (optional check)
276    ///
277    /// If set, the optimizer checks if condition_number(J^T*J) exceeds this
278    /// threshold and terminates with IllConditionedJacobian status.
279    /// Note: Computing condition number is expensive, so this is disabled by default.
280    ///
281    /// Default: None (disabled)
282    pub max_condition_number: Option<f64>,
283
284    /// Compute per-variable covariance matrices (uncertainty estimation)
285    ///
286    /// When enabled, computes covariance by inverting the Hessian matrix after
287    /// convergence. The full covariance matrix is extracted into per-variable
288    /// blocks stored in both Variable structs and optimier::SolverResult.
289    ///
290    /// Default: false (to avoid performance overhead)
291    pub compute_covariances: bool,
292
293    /// Enable real-time visualization (graphical debugging).
294    ///
295    /// When enabled, optimization progress is logged to a Rerun viewer.
296    /// Note: Has zero overhead when disabled.
297    ///
298    /// Default: false
299    pub enable_visualization: bool,
300}
301
302impl Default for GaussNewtonConfig {
303    fn default() -> Self {
304        Self {
305            linear_solver_type: linalg::LinearSolverType::default(),
306            // Ceres Solver default: 50 (changed from 100 for compatibility)
307            max_iterations: 50,
308            // Ceres Solver default: 1e-6 (changed from 1e-8 for compatibility)
309            cost_tolerance: 1e-6,
310            // Ceres Solver default: 1e-8 (unchanged)
311            parameter_tolerance: 1e-8,
312            // Ceres Solver default: 1e-10 (changed from 1e-8 for compatibility)
313            gradient_tolerance: 1e-10,
314            timeout: None,
315            verbose: false,
316            use_jacobi_scaling: false,
317            min_diagonal: 1e-10,
318            // New Ceres-compatible termination parameters
319            min_cost_threshold: None,
320            max_condition_number: None,
321            compute_covariances: false,
322            enable_visualization: false,
323        }
324    }
325}
326
327impl GaussNewtonConfig {
328    /// Create a new Gauss-Newton configuration with default values.
329    pub fn new() -> Self {
330        Self::default()
331    }
332
333    /// Set the linear solver type
334    pub fn with_linear_solver_type(mut self, linear_solver_type: linalg::LinearSolverType) -> Self {
335        self.linear_solver_type = linear_solver_type;
336        self
337    }
338
339    /// Set the maximum number of iterations
340    pub fn with_max_iterations(mut self, max_iterations: usize) -> Self {
341        self.max_iterations = max_iterations;
342        self
343    }
344
345    /// Set the cost tolerance
346    pub fn with_cost_tolerance(mut self, cost_tolerance: f64) -> Self {
347        self.cost_tolerance = cost_tolerance;
348        self
349    }
350
351    /// Set the parameter tolerance
352    pub fn with_parameter_tolerance(mut self, parameter_tolerance: f64) -> Self {
353        self.parameter_tolerance = parameter_tolerance;
354        self
355    }
356
357    /// Set the gradient tolerance
358    pub fn with_gradient_tolerance(mut self, gradient_tolerance: f64) -> Self {
359        self.gradient_tolerance = gradient_tolerance;
360        self
361    }
362
363    /// Set the timeout duration
364    pub fn with_timeout(mut self, timeout: time::Duration) -> Self {
365        self.timeout = Some(timeout);
366        self
367    }
368
369    /// Enable or disable verbose logging
370    pub fn with_verbose(mut self, verbose: bool) -> Self {
371        self.verbose = verbose;
372        self
373    }
374
375    /// Enable or disable Jacobi column scaling (preconditioning).
376    ///
377    /// When enabled, normalizes Jacobian columns by their L2 norm before solving.
378    /// Can improve convergence for mixed-scale problems but adds ~5-10% overhead.
379    pub fn with_jacobi_scaling(mut self, use_jacobi_scaling: bool) -> Self {
380        self.use_jacobi_scaling = use_jacobi_scaling;
381        self
382    }
383
384    /// Set the minimum diagonal regularization for numerical stability.
385    ///
386    /// A small value (e.g., 1e-10) ensures J^T·J is positive definite while
387    /// maintaining the fast convergence of pure Gauss-Newton.
388    pub fn with_min_diagonal(mut self, min_diagonal: f64) -> Self {
389        self.min_diagonal = min_diagonal;
390        self
391    }
392
393    /// Set minimum objective function cutoff for early termination.
394    ///
395    /// When set, optimization terminates with MinCostThresholdReached status
396    /// if the cost falls below this threshold. Useful for early stopping when
397    /// a "good enough" solution is acceptable.
398    pub fn with_min_cost_threshold(mut self, min_cost: f64) -> Self {
399        self.min_cost_threshold = Some(min_cost);
400        self
401    }
402
403    /// Set maximum condition number for Jacobian matrix.
404    ///
405    /// If set, the optimizer checks if condition_number(J^T*J) exceeds this
406    /// threshold and terminates with IllConditionedJacobian status.
407    /// Note: Computing condition number is expensive, disabled by default.
408    pub fn with_max_condition_number(mut self, max_cond: f64) -> Self {
409        self.max_condition_number = Some(max_cond);
410        self
411    }
412
413    /// Enable or disable covariance computation (uncertainty estimation).
414    ///
415    /// When enabled, computes the full covariance matrix by inverting the Hessian
416    /// after convergence, then extracts per-variable covariance blocks.
417    pub fn with_compute_covariances(mut self, compute_covariances: bool) -> Self {
418        self.compute_covariances = compute_covariances;
419        self
420    }
421
422    /// Enable real-time visualization.
423    ///
424    /// # Arguments
425    ///
426    /// * `enable` - Whether to enable visualization
427    pub fn with_visualization(mut self, enable: bool) -> Self {
428        self.enable_visualization = enable;
429        self
430    }
431}
432
433/// State for optimization iteration
434struct LinearizerResult {
435    variables: collections::HashMap<String, problem::VariableEnum>,
436    variable_index_map: collections::HashMap<String, usize>,
437    sorted_vars: Vec<String>,
438    symbolic_structure: problem::SymbolicStructure,
439    current_cost: f64,
440    initial_cost: f64,
441}
442
443/// Result from step computation
444struct StepResult {
445    step: faer::Mat<f64>,
446    gradient_norm: f64,
447}
448
449/// Result from cost evaluation
450struct CostEvaluation {
451    new_cost: f64,
452    cost_reduction: f64,
453}
454
455/// Gauss-Newton solver for nonlinear least squares optimization.
456///
457/// Implements the classical Gauss-Newton algorithm which solves `J^T·J·h = -J^T·r` at each
458/// iteration to find the step `h`. This provides fast quadratic convergence near the solution
459/// but may diverge for poor initial guesses or ill-conditioned problems.
460///
461/// # Algorithm
462///
463/// At each iteration k:
464/// 1. Compute residual `r(xₖ)` and Jacobian `J(xₖ)`
465/// 2. Form normal equations: `(J^T·J)·h = -J^T·r`
466/// 3. Solve for step `h` using Cholesky or QR factorization
467/// 4. Update parameters: `xₖ₊₁ = xₖ ⊕ h` (manifold plus operation)
468/// 5. Check convergence criteria
469///
470/// # Examples
471///
472/// ```no_run
473/// use apex_solver::optimizer::GaussNewton;
474/// use apex_solver::core::problem::Problem;
475/// use std::collections::HashMap;
476///
477/// # fn main() -> Result<(), Box<dyn std::error::Error>> {
478/// let mut problem = Problem::new();
479/// // ... add factors to problem ...
480///
481/// let initial_values = HashMap::new();
482/// // ... initialize parameters ...
483///
484/// let mut solver = GaussNewton::new();
485/// let result = solver.optimize(&problem, &initial_values)?;
486///
487/// println!("Status: {:?}", result.status);
488/// println!("Final cost: {}", result.final_cost);
489/// # Ok(())
490/// # }
491/// ```
492///
493/// # See Also
494///
495/// - [`GaussNewtonConfig`] - Configuration options
496/// - [`LevenbergMarquardt`](crate::optimizer::LevenbergMarquardt) - For adaptive damping
497/// - [`DogLeg`](crate::optimizer::DogLeg) - For trust region control
498pub struct GaussNewton {
499    config: GaussNewtonConfig,
500    jacobi_scaling: Option<sparse::SparseColMat<usize, f64>>,
501    visualizer: Option<optimizer::visualization::OptimizationVisualizer>,
502}
503
504impl Default for GaussNewton {
505    fn default() -> Self {
506        Self::new()
507    }
508}
509
510impl GaussNewton {
511    /// Create a new Gauss-Newton solver with default configuration.
512    pub fn new() -> Self {
513        Self::with_config(GaussNewtonConfig::default())
514    }
515
516    /// Create a new Gauss-Newton solver with the given configuration.
517    pub fn with_config(config: GaussNewtonConfig) -> Self {
518        // Create visualizer if enabled (zero overhead when disabled)
519        let visualizer = if config.enable_visualization {
520            optimizer::visualization::OptimizationVisualizer::new(true).ok()
521        } else {
522            None
523        };
524
525        Self {
526            config,
527            jacobi_scaling: None,
528            visualizer,
529        }
530    }
531
532    /// Create the appropriate linear solver based on configuration
533    fn create_linear_solver(&self) -> Box<dyn linalg::SparseLinearSolver> {
534        match self.config.linear_solver_type {
535            linalg::LinearSolverType::SparseCholesky => {
536                Box::new(linalg::SparseCholeskySolver::new())
537            }
538            linalg::LinearSolverType::SparseQR => Box::new(linalg::SparseQRSolver::new()),
539        }
540    }
541
542    /// Check convergence criteria
543    /// Check convergence using comprehensive termination criteria.
544    ///
545    /// Implements 8 termination criteria following Ceres Solver standards for Gauss-Newton:
546    ///
547    /// 1. **Gradient Norm (First-Order Optimality)**: ||g||∞ ≤ gradient_tolerance
548    /// 2. **Parameter Change Tolerance**: ||h|| ≤ parameter_tolerance * (||x|| + parameter_tolerance)
549    /// 3. **Function Value Change Tolerance**: |ΔF| < cost_tolerance * F
550    /// 4. **Objective Function Cutoff**: F_new < min_cost_threshold (optional)
551    /// 5. **Singular/Ill-Conditioned Jacobian**: Detected during linear solve
552    /// 6. **Invalid Numerical Values**: NaN or Inf in cost or parameters
553    /// 7. **Maximum Iterations**: iteration >= max_iterations
554    /// 8. **Timeout**: elapsed >= timeout
555    ///
556    /// **Note**: Trust region radius termination is NOT applicable to Gauss-Newton
557    /// as it is a line search method, not a trust region method.
558    ///
559    /// # Arguments
560    ///
561    /// * `iteration` - Current iteration number
562    /// * `current_cost` - Cost before applying the step
563    /// * `new_cost` - Cost after applying the step
564    /// * `parameter_norm` - L2 norm of current parameter vector ||x||
565    /// * `parameter_update_norm` - L2 norm of parameter update step ||h||
566    /// * `gradient_norm` - Infinity norm of gradient ||g||∞
567    /// * `elapsed` - Elapsed time since optimization start
568    ///
569    /// # Returns
570    ///
571    /// `Some(OptimizationStatus)` if any termination criterion is satisfied, `None` otherwise.
572    #[allow(clippy::too_many_arguments)]
573    fn check_convergence(
574        &self,
575        iteration: usize,
576        current_cost: f64,
577        new_cost: f64,
578        parameter_norm: f64,
579        parameter_update_norm: f64,
580        gradient_norm: f64,
581        elapsed: time::Duration,
582    ) -> Option<optimizer::OptimizationStatus> {
583        // ========================================================================
584        // CRITICAL SAFETY CHECKS (perform first, before convergence checks)
585        // ========================================================================
586
587        // CRITERION 6: Invalid Numerical Values (NaN/Inf)
588        // Always check for numerical instability first
589        if !new_cost.is_finite() || !parameter_update_norm.is_finite() || !gradient_norm.is_finite()
590        {
591            return Some(optimizer::OptimizationStatus::InvalidNumericalValues);
592        }
593
594        // CRITERION 8: Timeout
595        // Check wall-clock time limit
596        if let Some(timeout) = self.config.timeout
597            && elapsed >= timeout
598        {
599            return Some(optimizer::OptimizationStatus::Timeout);
600        }
601
602        // CRITERION 7: Maximum Iterations
603        // Check iteration count limit
604        if iteration >= self.config.max_iterations {
605            return Some(optimizer::OptimizationStatus::MaxIterationsReached);
606        }
607
608        // ========================================================================
609        // CONVERGENCE CRITERIA
610        // ========================================================================
611        // Note: Gauss-Newton always accepts the computed step (no step acceptance check)
612
613        // CRITERION 1: Gradient Norm (First-Order Optimality)
614        // Check if gradient infinity norm is below threshold
615        // This indicates we're at a critical point (local minimum, saddle, or maximum)
616        if gradient_norm < self.config.gradient_tolerance {
617            return Some(optimizer::OptimizationStatus::GradientToleranceReached);
618        }
619
620        // Only check parameter and cost criteria after first iteration
621        if iteration > 0 {
622            // CRITERION 2: Parameter Change Tolerance (xtol)
623            // Ceres formula: ||h|| ≤ ε_param * (||x|| + ε_param)
624            // This is a relative measure that scales with parameter magnitude
625            let relative_step_tolerance = self.config.parameter_tolerance
626                * (parameter_norm + self.config.parameter_tolerance);
627
628            if parameter_update_norm <= relative_step_tolerance {
629                return Some(optimizer::OptimizationStatus::ParameterToleranceReached);
630            }
631
632            // CRITERION 3: Function Value Change Tolerance (ftol)
633            // Ceres formula: |ΔF| < ε_cost * F
634            // Check relative cost change (not absolute)
635            let cost_change = (current_cost - new_cost).abs();
636            let relative_cost_change = cost_change / current_cost.max(1e-10); // Avoid division by zero
637
638            if relative_cost_change < self.config.cost_tolerance {
639                return Some(optimizer::OptimizationStatus::CostToleranceReached);
640            }
641        }
642
643        // CRITERION 4: Objective Function Cutoff (optional early stopping)
644        // Useful for "good enough" solutions
645        if let Some(min_cost) = self.config.min_cost_threshold
646            && new_cost < min_cost
647        {
648            return Some(optimizer::OptimizationStatus::MinCostThresholdReached);
649        }
650
651        // CRITERION 5: Singular/Ill-Conditioned Jacobian
652        // Note: This is typically detected during the linear solve and handled there
653        // The max_condition_number check would be expensive to compute here
654        // If linear solve fails, it returns an error that's converted to NumericalFailure
655
656        // No termination criterion satisfied
657        None
658    }
659
660    /// Compute total parameter vector norm ||x||.
661    ///
662    /// Computes the L2 norm of all parameter vectors concatenated together.
663    /// This is used in the relative parameter tolerance check.
664    ///
665    /// # Arguments
666    ///
667    /// * `variables` - Map of variable names to their current values
668    ///
669    /// # Returns
670    ///
671    /// The L2 norm of the concatenated parameter vector
672    fn compute_parameter_norm(
673        variables: &collections::HashMap<String, problem::VariableEnum>,
674    ) -> f64 {
675        variables
676            .values()
677            .map(|v| {
678                let vec = v.to_vector();
679                vec.norm_squared()
680            })
681            .sum::<f64>()
682            .sqrt()
683    }
684
685    /// Create Jacobi scaling matrix from Jacobian
686    fn create_jacobi_scaling(
687        &self,
688        jacobian: &sparse::SparseColMat<usize, f64>,
689    ) -> sparse::SparseColMat<usize, f64> {
690        use faer::sparse::Triplet;
691
692        let cols = jacobian.ncols();
693        let jacobi_scaling_vec: Vec<Triplet<usize, usize, f64>> = (0..cols)
694            .map(|c| {
695                // Compute column norm: sqrt(sum(J_col^2))
696                let col_norm_squared: f64 = jacobian
697                    .triplet_iter()
698                    .filter(|t| t.col == c)
699                    .map(|t| t.val * t.val)
700                    .sum();
701                let col_norm = col_norm_squared.sqrt();
702                // Scaling factor: 1.0 / (1.0 + col_norm)
703                let scaling = 1.0 / (1.0 + col_norm);
704                Triplet::new(c, c, scaling)
705            })
706            .collect();
707
708        sparse::SparseColMat::try_new_from_triplets(cols, cols, &jacobi_scaling_vec)
709            .expect("Failed to create Jacobi scaling matrix")
710    }
711
712    /// Initialize optimization state from problem and initial parameters
713    fn initialize_optimization_state(
714        &self,
715        problem: &problem::Problem,
716        initial_params: &collections::HashMap<
717            String,
718            (manifold::ManifoldType, nalgebra::DVector<f64>),
719        >,
720    ) -> Result<LinearizerResult, error::ApexError> {
721        // Initialize variables from initial values
722        let variables = problem.initialize_variables(initial_params);
723
724        // Create column mapping for variables
725        let mut variable_index_map = collections::HashMap::new();
726        let mut col_offset = 0;
727        let mut sorted_vars: Vec<String> = variables.keys().cloned().collect();
728        sorted_vars.sort();
729
730        for var_name in &sorted_vars {
731            variable_index_map.insert(var_name.clone(), col_offset);
732            col_offset += variables[var_name].get_size();
733        }
734
735        // Build symbolic structure for sparse operations
736        let symbolic_structure =
737            problem.build_symbolic_structure(&variables, &variable_index_map, col_offset)?;
738
739        // Initial cost evaluation (residual only, no Jacobian needed)
740        let residual = problem.compute_residual_sparse(&variables)?;
741        let current_cost = optimizer::compute_cost(&residual);
742        let initial_cost = current_cost;
743
744        if self.config.verbose {
745            println!(
746                "Starting Gauss-Newton optimization with {} max iterations",
747                self.config.max_iterations
748            );
749            println!("Initial cost: {:.6e}", current_cost);
750        }
751
752        Ok(LinearizerResult {
753            variables,
754            variable_index_map,
755            sorted_vars,
756            symbolic_structure,
757            current_cost,
758            initial_cost,
759        })
760    }
761
762    /// Process Jacobian by creating and applying Jacobi scaling if enabled
763    fn process_jacobian(
764        &mut self,
765        jacobian: &sparse::SparseColMat<usize, f64>,
766        iteration: usize,
767    ) -> sparse::SparseColMat<usize, f64> {
768        // Create Jacobi scaling on first iteration if enabled
769        if iteration == 0 {
770            let scaling = self.create_jacobi_scaling(jacobian);
771
772            if self.config.verbose {
773                println!("Jacobi scaling computed for {} columns", scaling.ncols());
774            }
775
776            self.jacobi_scaling = Some(scaling);
777        }
778        jacobian * self.jacobi_scaling.as_ref().unwrap()
779    }
780
781    /// Compute Gauss-Newton step by solving the normal equations
782    fn compute_gauss_newton_step(
783        &self,
784        residuals: &faer::Mat<f64>,
785        scaled_jacobian: &sparse::SparseColMat<usize, f64>,
786        linear_solver: &mut Box<dyn linalg::SparseLinearSolver>,
787    ) -> Option<StepResult> {
788        // Solve the Gauss-Newton equation: J^T·J·Δx = -J^T·r
789        // Use min_diagonal for numerical stability (tiny regularization)
790        let residuals_owned = residuals.as_ref().to_owned();
791        let scaled_step = linear_solver
792            .solve_normal_equation(&residuals_owned, scaled_jacobian)
793            .ok()?;
794
795        // Get gradient from the solver (J^T * r)
796        let gradient = linear_solver.get_gradient()?;
797        // Compute gradient norm for convergence check
798        let gradient_norm = gradient.norm_l2();
799
800        if self.config.verbose {
801            println!("Gradient (J^T*r) norm: {:.12e}", gradient_norm);
802        }
803
804        // Apply inverse Jacobi scaling to get final step (if enabled)
805        let step = if self.config.use_jacobi_scaling {
806            &scaled_step * self.jacobi_scaling.as_ref().unwrap()
807        } else {
808            scaled_step
809        };
810
811        if self.config.verbose {
812            println!("Step norm: {:.12e}", step.norm_l2());
813        }
814
815        Some(StepResult {
816            step,
817            gradient_norm,
818        })
819    }
820
821    /// Apply step to parameters and evaluate new cost
822    fn apply_step_and_evaluate_cost(
823        &self,
824        step_result: &StepResult,
825        state: &mut LinearizerResult,
826        problem: &problem::Problem,
827    ) -> error::ApexResult<CostEvaluation> {
828        // Apply parameter updates using manifold operations
829        let _step_norm = optimizer::apply_parameter_step(
830            &mut state.variables,
831            step_result.step.as_ref(),
832            &state.sorted_vars,
833        );
834
835        // Compute new cost (residual only, no Jacobian needed for step evaluation)
836        let new_residual = problem.compute_residual_sparse(&state.variables)?;
837        let new_cost = optimizer::compute_cost(&new_residual);
838
839        // Compute cost reduction
840        let cost_reduction = state.current_cost - new_cost;
841
842        // Update current cost
843        state.current_cost = new_cost;
844
845        Ok(CostEvaluation {
846            new_cost,
847            cost_reduction,
848        })
849    }
850
851    /// Log iteration details if verbose mode is enabled
852    fn log_iteration(&self, iteration: usize, cost_eval: &CostEvaluation, step_norm: f64) {
853        if !self.config.verbose {
854            return;
855        }
856
857        println!(
858            "Iteration {}: cost = {:.6e}, reduction = {:.6e}, step_norm = {:.6e}",
859            iteration + 1,
860            cost_eval.new_cost,
861            cost_eval.cost_reduction,
862            step_norm
863        );
864    }
865
866    /// Create optimization summary
867    #[allow(clippy::too_many_arguments)]
868    fn create_summary(
869        &self,
870        initial_cost: f64,
871        final_cost: f64,
872        iterations: usize,
873        max_gradient_norm: f64,
874        final_gradient_norm: f64,
875        max_parameter_update_norm: f64,
876        final_parameter_update_norm: f64,
877        total_cost_reduction: f64,
878        total_time: time::Duration,
879    ) -> GaussNewtonSummary {
880        GaussNewtonSummary {
881            initial_cost,
882            final_cost,
883            iterations,
884            average_cost_reduction: if iterations > 0 {
885                total_cost_reduction / iterations as f64
886            } else {
887                0.0
888            },
889            max_gradient_norm,
890            final_gradient_norm,
891            max_parameter_update_norm,
892            final_parameter_update_norm,
893            total_time,
894            average_time_per_iteration: if iterations > 0 {
895                total_time / iterations as u32
896            } else {
897                time::Duration::from_secs(0)
898            },
899        }
900    }
901
902    pub fn optimize(
903        &mut self,
904        problem: &problem::Problem,
905        initial_params: &collections::HashMap<
906            String,
907            (manifold::ManifoldType, nalgebra::DVector<f64>),
908        >,
909    ) -> Result<
910        optimizer::SolverResult<collections::HashMap<String, problem::VariableEnum>>,
911        error::ApexError,
912    > {
913        let start_time = time::Instant::now();
914        let mut iteration = 0;
915        let mut cost_evaluations = 1; // Initial cost evaluation
916        let mut jacobian_evaluations = 0;
917
918        // Initialize optimization state
919        let mut state = self.initialize_optimization_state(problem, initial_params)?;
920
921        // Create linear solver
922        let mut linear_solver = self.create_linear_solver();
923
924        // Initialize summary tracking variables
925        let mut max_gradient_norm: f64 = 0.0;
926        let mut max_parameter_update_norm: f64 = 0.0;
927        let mut total_cost_reduction = 0.0;
928        let mut final_gradient_norm;
929        let mut final_parameter_update_norm;
930
931        // Main optimization loop
932        loop {
933            // Evaluate residuals and Jacobian
934            let (residuals, jacobian) = problem.compute_residual_and_jacobian_sparse(
935                &state.variables,
936                &state.variable_index_map,
937                &state.symbolic_structure,
938            )?;
939            jacobian_evaluations += 1;
940
941            if self.config.verbose {
942                println!("\n=== GAUSS-NEWTON ITERATION {} ===", iteration);
943                println!("Current cost: {:.12e}", state.current_cost);
944                println!(
945                    "Residuals shape: ({}, {})",
946                    residuals.nrows(),
947                    residuals.ncols()
948                );
949                println!("Residuals norm: {:.12e}", residuals.norm_l2());
950                println!(
951                    "Jacobian shape: ({}, {})",
952                    jacobian.nrows(),
953                    jacobian.ncols()
954                );
955            }
956
957            // Process Jacobian (apply scaling if enabled)
958            let scaled_jacobian = if self.config.use_jacobi_scaling {
959                self.process_jacobian(&jacobian, iteration)
960            } else {
961                jacobian
962            };
963
964            if self.config.verbose {
965                println!(
966                    "Scaled Jacobian shape: ({}, {})",
967                    scaled_jacobian.nrows(),
968                    scaled_jacobian.ncols()
969                );
970            }
971
972            // Compute Gauss-Newton step
973            let step_result = match self.compute_gauss_newton_step(
974                &residuals,
975                &scaled_jacobian,
976                &mut linear_solver,
977            ) {
978                Some(result) => result,
979                None => {
980                    return Err(error::ApexError::Solver(
981                        "Linear solver failed to solve Gauss-Newton system".to_string(),
982                    ));
983                }
984            };
985
986            // Update tracking variables
987            max_gradient_norm = max_gradient_norm.max(step_result.gradient_norm);
988            final_gradient_norm = step_result.gradient_norm;
989            let step_norm = step_result.step.norm_l2();
990            max_parameter_update_norm = max_parameter_update_norm.max(step_norm);
991            final_parameter_update_norm = step_norm;
992
993            // Capture cost before applying step (for convergence check)
994            let cost_before_step = state.current_cost;
995
996            // Apply step and evaluate new cost
997            let cost_eval = self.apply_step_and_evaluate_cost(&step_result, &mut state, problem)?;
998            cost_evaluations += 1;
999            total_cost_reduction += cost_eval.cost_reduction;
1000
1001            // Log iteration
1002            if self.config.verbose {
1003                self.log_iteration(iteration, &cost_eval, step_norm);
1004            };
1005
1006            // Rerun visualization
1007            if let Some(ref vis) = self.visualizer {
1008                if let Err(e) = vis.log_scalars(
1009                    iteration,
1010                    state.current_cost,
1011                    step_result.gradient_norm,
1012                    0.0, // Gauss-Newton doesn't use damping/trust region
1013                    step_norm,
1014                    None, // No step quality rho in Gauss-Newton
1015                ) {
1016                    eprintln!("[WARNING] Failed to log scalars: {}", e);
1017                }
1018
1019                // Log expensive visualizations (Hessian, gradient, manifolds)
1020                if let Err(e) = vis.log_hessian(linear_solver.get_hessian(), iteration) {
1021                    eprintln!("[WARNING] Failed to log Hessian: {}", e);
1022                }
1023                if let Err(e) = vis.log_gradient(linear_solver.get_gradient(), iteration) {
1024                    eprintln!("[WARNING] Failed to log gradient: {}", e);
1025                }
1026                if let Err(e) = vis.log_manifolds(&state.variables, iteration) {
1027                    eprintln!("[WARNING] Failed to log manifolds: {}", e);
1028                }
1029            }
1030
1031            // Compute parameter norm for convergence check
1032            let parameter_norm = Self::compute_parameter_norm(&state.variables);
1033
1034            // Check convergence using comprehensive termination criteria
1035            let elapsed = start_time.elapsed();
1036            if let Some(status) = self.check_convergence(
1037                iteration,
1038                cost_before_step,
1039                cost_eval.new_cost,
1040                parameter_norm,
1041                step_norm,
1042                step_result.gradient_norm,
1043                elapsed,
1044            ) {
1045                let summary = self.create_summary(
1046                    state.initial_cost,
1047                    state.current_cost,
1048                    iteration + 1,
1049                    max_gradient_norm,
1050                    final_gradient_norm,
1051                    max_parameter_update_norm,
1052                    final_parameter_update_norm,
1053                    total_cost_reduction,
1054                    elapsed,
1055                );
1056
1057                if self.config.verbose {
1058                    println!("{}", summary);
1059                }
1060
1061                // Compute covariances if enabled
1062                let covariances = if self.config.compute_covariances {
1063                    problem.compute_and_set_covariances(
1064                        &mut linear_solver,
1065                        &mut state.variables,
1066                        &state.variable_index_map,
1067                    )
1068                } else {
1069                    None
1070                };
1071
1072                return Ok(optimizer::SolverResult {
1073                    status,
1074                    iterations: iteration + 1,
1075                    initial_cost: state.initial_cost,
1076                    final_cost: state.current_cost,
1077                    parameters: state.variables.into_iter().collect(),
1078                    elapsed_time: elapsed,
1079                    convergence_info: Some(optimizer::ConvergenceInfo {
1080                        final_gradient_norm,
1081                        final_parameter_update_norm,
1082                        cost_evaluations,
1083                        jacobian_evaluations,
1084                    }),
1085                    covariances,
1086                });
1087            }
1088
1089            iteration += 1;
1090        }
1091    }
1092}
1093
1094impl optimizer::Solver for GaussNewton {
1095    type Config = GaussNewtonConfig;
1096    type Error = error::ApexError;
1097
1098    fn new() -> Self {
1099        Self::default()
1100    }
1101
1102    fn optimize(
1103        &mut self,
1104        problem: &problem::Problem,
1105        initial_params: &std::collections::HashMap<
1106            String,
1107            (manifold::ManifoldType, nalgebra::DVector<f64>),
1108        >,
1109    ) -> Result<
1110        optimizer::SolverResult<std::collections::HashMap<String, problem::VariableEnum>>,
1111        Self::Error,
1112    > {
1113        self.optimize(problem, initial_params)
1114    }
1115}
1116
1117#[cfg(test)]
1118mod tests {
1119    use crate::{
1120        core::{factors, problem},
1121        manifold, optimizer,
1122    };
1123    use nalgebra::dvector;
1124    use std::collections;
1125
1126    /// Custom Rosenbrock Factor 1: r1 = 10(x2 - x1²)
1127    /// Demonstrates extensibility - custom factors can be defined outside of factors.rs
1128    #[derive(Debug, Clone)]
1129    struct RosenbrockFactor1;
1130
1131    impl factors::Factor for RosenbrockFactor1 {
1132        fn linearize(
1133            &self,
1134            params: &[nalgebra::DVector<f64>],
1135            compute_jacobian: bool,
1136        ) -> (nalgebra::DVector<f64>, Option<nalgebra::DMatrix<f64>>) {
1137            let x1 = params[0][0];
1138            let x2 = params[1][0];
1139
1140            // Residual: r1 = 10(x2 - x1²)
1141            let residual = nalgebra::dvector![10.0 * (x2 - x1 * x1)];
1142
1143            // Jacobian: ∂r1/∂x1 = -20*x1, ∂r1/∂x2 = 10
1144            let jacobian = if compute_jacobian {
1145                let mut jac = nalgebra::DMatrix::zeros(1, 2);
1146                jac[(0, 0)] = -20.0 * x1;
1147                jac[(0, 1)] = 10.0;
1148                Some(jac)
1149            } else {
1150                None
1151            };
1152
1153            (residual, jacobian)
1154        }
1155
1156        fn get_dimension(&self) -> usize {
1157            1
1158        }
1159    }
1160
1161    /// Custom Rosenbrock Factor 2: r2 = 1 - x1
1162    /// Demonstrates extensibility - custom factors can be defined outside of factors.rs
1163    #[derive(Debug, Clone)]
1164    struct RosenbrockFactor2;
1165
1166    impl factors::Factor for RosenbrockFactor2 {
1167        fn linearize(
1168            &self,
1169            params: &[nalgebra::DVector<f64>],
1170            compute_jacobian: bool,
1171        ) -> (nalgebra::DVector<f64>, Option<nalgebra::DMatrix<f64>>) {
1172            let x1 = params[0][0];
1173
1174            // Residual: r2 = 1 - x1
1175            let residual = nalgebra::dvector![1.0 - x1];
1176
1177            // Jacobian: ∂r2/∂x1 = -1
1178            let jacobian = if compute_jacobian {
1179                Some(nalgebra::DMatrix::from_element(1, 1, -1.0))
1180            } else {
1181                None
1182            };
1183
1184            (residual, jacobian)
1185        }
1186
1187        fn get_dimension(&self) -> usize {
1188            1
1189        }
1190    }
1191
1192    #[test]
1193    fn test_rosenbrock_optimization() {
1194        // Rosenbrock function test:
1195        // Minimize: r1² + r2² where
1196        //   r1 = 10(x2 - x1²)
1197        //   r2 = 1 - x1
1198        // Starting point: [-1.2, 1.0]
1199        // Expected minimum: [1.0, 1.0]
1200
1201        let mut problem = problem::Problem::new();
1202        let mut initial_values = collections::HashMap::new();
1203
1204        // Add variables using Rn manifold (Euclidean space)
1205        initial_values.insert(
1206            "x1".to_string(),
1207            (manifold::ManifoldType::RN, dvector![-1.2]),
1208        );
1209        initial_values.insert(
1210            "x2".to_string(),
1211            (manifold::ManifoldType::RN, dvector![1.0]),
1212        );
1213
1214        // Add custom factors (demonstrates extensibility!)
1215        problem.add_residual_block(&["x1", "x2"], Box::new(RosenbrockFactor1), None);
1216        problem.add_residual_block(&["x1"], Box::new(RosenbrockFactor2), None);
1217
1218        // Configure Gauss-Newton optimizer
1219        let config = optimizer::gauss_newton::GaussNewtonConfig::new()
1220            .with_max_iterations(100)
1221            .with_cost_tolerance(1e-8)
1222            .with_parameter_tolerance(1e-8)
1223            .with_gradient_tolerance(1e-10);
1224
1225        let mut solver = optimizer::GaussNewton::with_config(config);
1226        let result = solver.optimize(&problem, &initial_values).unwrap();
1227
1228        // Extract final values
1229        let x1_final = result.parameters.get("x1").unwrap().to_vector()[0];
1230        let x2_final = result.parameters.get("x2").unwrap().to_vector()[0];
1231
1232        println!("Rosenbrock optimization result (Gauss-Newton):");
1233        println!("  Status: {:?}", result.status);
1234        println!("  Initial cost: {:.6e}", result.initial_cost);
1235        println!("  Final cost: {:.6e}", result.final_cost);
1236        println!("  Iterations: {}", result.iterations);
1237        println!("  x1: {:.6} (expected 1.0)", x1_final);
1238        println!("  x2: {:.6} (expected 1.0)", x2_final);
1239
1240        // Verify convergence to [1.0, 1.0]
1241        assert!(
1242            matches!(
1243                result.status,
1244                optimizer::OptimizationStatus::Converged
1245                    | optimizer::OptimizationStatus::CostToleranceReached
1246                    | optimizer::OptimizationStatus::ParameterToleranceReached
1247                    | optimizer::OptimizationStatus::GradientToleranceReached
1248            ),
1249            "Optimization should converge"
1250        );
1251        assert!(
1252            (x1_final - 1.0).abs() < 1e-4,
1253            "x1 should converge to 1.0, got {}",
1254            x1_final
1255        );
1256        assert!(
1257            (x2_final - 1.0).abs() < 1e-4,
1258            "x2 should converge to 1.0, got {}",
1259            x2_final
1260        );
1261        assert!(
1262            result.final_cost < 1e-6,
1263            "Final cost should be near zero, got {}",
1264            result.final_cost
1265        );
1266    }
1267}