Skip to main content

apex_solver/optimizer/
mod.rs

1//! Optimization solvers for nonlinear least squares problems.
2//!
3//! This module provides various optimization algorithms specifically designed
4//! for nonlinear least squares problems commonly found in computer vision:
5//! - Levenberg-Marquardt algorithm
6//! - Gauss-Newton algorithm
7//! - Dog Leg algorithm
8
9use crate::core::problem::{Problem, VariableEnum};
10use crate::error::ErrorLogging;
11use crate::linalg::{
12    self, JacobianMode, LinearSolver, SparseCholeskySolver, SparseMode, SparseQRSolver,
13};
14use crate::linearizer::SymbolicStructure;
15use apex_manifolds::ManifoldType;
16use faer::sparse::{SparseColMat, Triplet};
17use faer::{Mat, MatRef};
18use nalgebra::DVector;
19use std::collections::HashMap;
20use std::time::{self, Duration};
21use std::{
22    fmt,
23    fmt::{Display, Formatter},
24};
25use thiserror::Error;
26use tracing::debug;
27
28pub mod dog_leg;
29pub mod gauss_newton;
30pub mod levenberg_marquardt;
31
32pub use dog_leg::DogLeg;
33pub use gauss_newton::GaussNewton;
34pub use levenberg_marquardt::LevenbergMarquardt;
35
36// Re-export observer types from the observers module
37pub use crate::observers::{OptObserver, OptObserverVec};
38
39// Re-export AssemblyBackend so optimizer sub-modules can import it from optimizer::
40pub use crate::linearizer::AssemblyBackend;
41
42/// Type of optimization solver algorithm to use
43#[derive(Default, Clone, Copy, PartialEq, Eq)]
44pub enum OptimizerType {
45    /// Levenberg-Marquardt algorithm (robust, adaptive damping)
46    #[default]
47    LevenbergMarquardt,
48    /// Gauss-Newton algorithm (fast convergence, may be unstable)
49    GaussNewton,
50    /// Dog Leg algorithm (trust region method)
51    DogLeg,
52}
53
54impl Display for OptimizerType {
55    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
56        match self {
57            OptimizerType::LevenbergMarquardt => write!(f, "Levenberg-Marquardt"),
58            OptimizerType::GaussNewton => write!(f, "Gauss-Newton"),
59            OptimizerType::DogLeg => write!(f, "Dog Leg"),
60        }
61    }
62}
63
64/// Optimizer-specific error types for apex-solver
65#[derive(Debug, Clone, Error)]
66pub enum OptimizerError {
67    /// Linear system solve failed during optimization
68    #[error("Linear system solve failed: {0}")]
69    LinearSolveFailed(String),
70
71    /// Maximum iterations reached without achieving convergence
72    #[error("Maximum iterations ({max_iters}) reached without convergence")]
73    MaxIterationsReached { max_iters: usize },
74
75    /// Trust region radius became too small
76    #[error("Trust region radius became too small: {radius:.6e} < {min_radius:.6e}")]
77    TrustRegionFailure { radius: f64, min_radius: f64 },
78
79    /// Damping parameter became too large (LM-specific)
80    #[error("Damping parameter became too large: {damping:.6e} > {max_damping:.6e}")]
81    DampingFailure { damping: f64, max_damping: f64 },
82
83    /// Cost increased unexpectedly when it should decrease
84    #[error("Cost increased unexpectedly: {old_cost:.6e} -> {new_cost:.6e}")]
85    CostIncrease { old_cost: f64, new_cost: f64 },
86
87    /// Jacobian computation failed
88    #[error("Jacobian computation failed: {0}")]
89    JacobianFailed(String),
90
91    /// Invalid optimization parameters provided
92    #[error("Invalid optimization parameters: {0}")]
93    InvalidParameters(String),
94
95    /// Numerical instability detected (NaN, Inf in cost, gradient, or parameters)
96    #[error("Numerical instability detected: {0}")]
97    NumericalInstability(String),
98
99    /// Linear algebra operation failed
100    ///
101    /// **Convention**: When a `LinAlgError` occurs during optimization, it wraps
102    /// here via `?` to preserve optimizer context. This ensures the error
103    /// propagates as `ApexSolverError::Optimizer(OptimizerError::LinAlg(...))`
104    /// at the API level, not `ApexSolverError::LinearAlgebra(...)`.
105    #[error("Linear algebra error: {0}")]
106    LinAlg(#[from] linalg::LinAlgError),
107
108    /// Core module error (problem construction, factor linearization)
109    ///
110    /// Wraps errors from the core module that occur during optimization,
111    /// such as symbolic structure failures or parallel computation errors.
112    #[error("Core error: {0}")]
113    Core(#[from] crate::core::CoreError),
114
115    /// Linearizer error (Jacobian assembly, symbolic structure)
116    ///
117    /// Wraps errors from the linearizer module that occur during optimization,
118    /// such as symbolic structure failures or variable mapping errors.
119    #[error("Linearizer error: {0}")]
120    Linearizer(#[from] crate::linearizer::LinearizerError),
121
122    /// Problem has no variables to optimize
123    #[error("Problem has no variables to optimize")]
124    EmptyProblem,
125
126    /// Problem has no residual blocks
127    #[error("Problem has no residual blocks")]
128    NoResidualBlocks,
129
130    /// Jacobi scaling matrix creation failed
131    #[error("Failed to create Jacobi scaling matrix: {0}")]
132    JacobiScalingCreation(String),
133
134    /// Jacobi scaling not initialized when expected
135    #[error("Jacobi scaling not initialized")]
136    JacobiScalingNotInitialized,
137
138    /// Unknown or unsupported linear solver type
139    #[error("Unknown linear solver type: {0}")]
140    UnknownLinearSolver(String),
141}
142
143/// Result type for optimizer operations
144pub type OptimizerResult<T> = Result<T, OptimizerError>;
145
146// State information during iterative optimization.
147// #[derive(Debug, Clone)]
148// pub struct IterativeState {
149//     /// Current iteration number
150//     pub iteration: usize,
151//     /// Current cost value
152//     pub cost: f64,
153//     /// Current gradient norm
154//     pub gradient_norm: f64,
155//     /// Current parameter update norm
156//     pub parameter_update_norm: f64,
157//     /// Time elapsed since start
158//     pub elapsed_time: Duration,
159// }
160
161/// Detailed convergence information.
162#[derive(Debug, Clone)]
163pub struct ConvergenceInfo {
164    /// Final gradient norm
165    pub final_gradient_norm: f64,
166    /// Final parameter update norm
167    pub final_parameter_update_norm: f64,
168    /// Cost function evaluation count
169    pub cost_evaluations: usize,
170    /// Jacobian evaluation count
171    pub jacobian_evaluations: usize,
172}
173
174impl Display for ConvergenceInfo {
175    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
176        write!(
177            f,
178            "Final gradient norm: {:.2e}, Final parameter update norm: {:.2e}, Cost evaluations: {}, Jacobian evaluations: {}",
179            self.final_gradient_norm,
180            self.final_parameter_update_norm,
181            self.cost_evaluations,
182            self.jacobian_evaluations
183        )
184    }
185}
186
187/// Status of an optimization process
188#[derive(Debug, Clone, PartialEq, Eq)]
189pub enum OptimizationStatus {
190    /// Optimization converged successfully
191    Converged,
192    /// Maximum number of iterations reached
193    MaxIterationsReached,
194    /// Cost function tolerance reached
195    CostToleranceReached,
196    /// Parameter tolerance reached
197    ParameterToleranceReached,
198    /// Gradient tolerance reached
199    GradientToleranceReached,
200    /// Optimization failed due to numerical issues
201    NumericalFailure,
202    /// User requested termination
203    UserTerminated,
204    /// Timeout reached
205    Timeout,
206    /// Trust region radius fell below minimum threshold
207    TrustRegionRadiusTooSmall,
208    /// Objective function fell below user-specified cutoff
209    MinCostThresholdReached,
210    /// Jacobian matrix is singular or ill-conditioned
211    IllConditionedJacobian,
212    /// NaN or Inf detected in cost or parameters
213    InvalidNumericalValues,
214    /// Other failure
215    Failed(String),
216}
217
218impl Display for OptimizationStatus {
219    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
220        match self {
221            OptimizationStatus::Converged => write!(f, "Converged"),
222            OptimizationStatus::MaxIterationsReached => write!(f, "Maximum iterations reached"),
223            OptimizationStatus::CostToleranceReached => write!(f, "Cost tolerance reached"),
224            OptimizationStatus::ParameterToleranceReached => {
225                write!(f, "Parameter tolerance reached")
226            }
227            OptimizationStatus::GradientToleranceReached => write!(f, "Gradient tolerance reached"),
228            OptimizationStatus::NumericalFailure => write!(f, "Numerical failure"),
229            OptimizationStatus::UserTerminated => write!(f, "User terminated"),
230            OptimizationStatus::Timeout => write!(f, "Timeout"),
231            OptimizationStatus::TrustRegionRadiusTooSmall => {
232                write!(f, "Trust region radius too small")
233            }
234            OptimizationStatus::MinCostThresholdReached => {
235                write!(f, "Minimum cost threshold reached")
236            }
237            OptimizationStatus::IllConditionedJacobian => {
238                write!(f, "Ill-conditioned Jacobian matrix")
239            }
240            OptimizationStatus::InvalidNumericalValues => {
241                write!(f, "Invalid numerical values (NaN/Inf) detected")
242            }
243            OptimizationStatus::Failed(msg) => write!(f, "Failed: {msg}"),
244        }
245    }
246}
247
248/// Result of a solver execution.
249#[derive(Clone)]
250pub struct SolverResult<T> {
251    /// Final parameters
252    pub parameters: T,
253    /// Final optimization status
254    pub status: OptimizationStatus,
255    /// Initial cost value
256    pub initial_cost: f64,
257    /// Final cost value
258    pub final_cost: f64,
259    /// Number of iterations performed
260    pub iterations: usize,
261    /// Total time elapsed
262    pub elapsed_time: time::Duration,
263    /// Convergence statistics
264    pub convergence_info: Option<ConvergenceInfo>,
265    /// Per-variable covariance matrices (uncertainty estimation)
266    ///
267    /// This is `None` if covariance computation was not enabled in the solver configuration.
268    /// When present, it contains a mapping from variable names to their covariance matrices
269    /// in tangent space. For example, for SE3 variables this would be 6×6 matrices.
270    ///
271    /// Enable covariance computation by setting `compute_covariances: true` in the optimizer config.
272    pub covariances: Option<HashMap<String, Mat<f64>>>,
273}
274
275/// Unified optimizer interface. Object-safe — `Box<dyn Optimizer>` is valid.
276///
277/// All three optimizers ([`LevenbergMarquardt`](crate::optimizer::levenberg_marquardt::LevenbergMarquardt),
278/// [`GaussNewton`](crate::optimizer::gauss_newton::GaussNewton),
279/// [`DogLeg`](crate::optimizer::dog_leg::DogLeg)) implement this trait.
280/// Each optimizer also provides inherent `new()`, `with_config()`, and `optimize()` methods
281/// for direct (non-polymorphic) usage.
282pub trait Optimizer {
283    /// Optimize the problem to minimize the cost function.
284    fn optimize(
285        &mut self,
286        problem: &Problem,
287        initial_params: &HashMap<String, (ManifoldType, DVector<f64>)>,
288    ) -> Result<SolverResult<HashMap<String, VariableEnum>>, crate::error::ApexSolverError>;
289}
290
291/// Apply parameter update step to all variables.
292///
293/// This is a common operation used by all optimizers (Levenberg-Marquardt, Gauss-Newton, Dog Leg).
294/// It applies a tangent space perturbation to each variable using the proper manifold plus operation.
295///
296/// # Arguments
297/// * `variables` - Mutable map of variables to update
298/// * `step` - Full step vector in tangent space (faer matrix view)
299/// * `variable_order` - Ordered list of variable names (defines indexing into step vector)
300///
301/// # Returns
302/// * Step norm (L2 norm) for convergence checking
303///
304/// # Implementation Notes
305/// The step vector contains concatenated tangent vectors for all variables in the order
306/// specified by `variable_order`. Each variable's tangent space dimension determines
307/// how many elements it occupies in the step vector.
308///
309pub fn apply_parameter_step(
310    variables: &mut HashMap<String, VariableEnum>,
311    step: MatRef<f64>,
312    variable_order: &[String],
313) -> f64 {
314    let mut step_offset = 0;
315
316    for var_name in variable_order {
317        if let Some(var) = variables.get_mut(var_name) {
318            let var_size = var.get_size();
319            let var_step = step.subrows(step_offset, var_size);
320
321            // Delegate to VariableEnum's apply_tangent_step method
322            // This handles all manifold types (SE2, SE3, SO2, SO3, Rn)
323            var.apply_tangent_step(var_step);
324
325            step_offset += var_size;
326        }
327    }
328
329    // Compute and return step norm for convergence checking
330    step.norm_l2()
331}
332
333/// Apply negative parameter step to rollback variables.
334///
335/// This is used when an optimization step is rejected (e.g., in trust region methods).
336/// It applies the negative of a tangent space perturbation to revert the previous update.
337///
338/// # Arguments
339/// * `variables` - Mutable map of variables to revert
340/// * `step` - Full step vector in tangent space (faer matrix view) to negate
341/// * `variable_order` - Ordered list of variable names (defines indexing into step vector)
342///
343pub fn apply_negative_parameter_step(
344    variables: &mut HashMap<String, VariableEnum>,
345    step: MatRef<f64>,
346    variable_order: &[String],
347) {
348    // Create a negated version of the step vector
349    let mut negative_step = Mat::zeros(step.nrows(), 1);
350    for i in 0..step.nrows() {
351        negative_step[(i, 0)] = -step[(i, 0)];
352    }
353
354    // Apply the negative step using the standard apply_parameter_step function
355    apply_parameter_step(variables, negative_step.as_ref(), variable_order);
356}
357
358pub fn compute_cost(residual: &Mat<f64>) -> f64 {
359    let cost = residual.norm_l2();
360    0.5 * cost * cost
361}
362
363// ============================================================================
364// Shared optimizer utilities
365// ============================================================================
366// The following types and functions are shared across all three optimizer
367// implementations (Levenberg-Marquardt, Gauss-Newton, Dog Leg) to eliminate
368// code duplication.
369
370/// Per-iteration statistics for detailed logging (Ceres-style output).
371///
372/// Captures all relevant metrics for each optimization iteration, enabling
373/// detailed analysis and debugging of the optimization process.
374#[derive(Debug, Clone)]
375pub struct IterationStats {
376    /// Iteration number (0-indexed)
377    pub iteration: usize,
378    /// Cost function value at this iteration
379    pub cost: f64,
380    /// Change in cost from previous iteration
381    pub cost_change: f64,
382    /// L2 norm of the gradient (||J^T·r||)
383    pub gradient_norm: f64,
384    /// L2 norm of the parameter update step (||Δx||)
385    pub step_norm: f64,
386    /// Trust region ratio (ρ = actual_reduction / predicted_reduction)
387    pub tr_ratio: f64,
388    /// Trust region radius (damping parameter λ for LM, Δ for Dog Leg)
389    pub tr_radius: f64,
390    /// Linear solver iterations (0 for direct solvers like Cholesky)
391    pub ls_iter: usize,
392    /// Time taken for this iteration in milliseconds
393    pub iter_time_ms: f64,
394    /// Total elapsed time since optimization started in milliseconds
395    pub total_time_ms: f64,
396    /// Whether the step was accepted (true) or rejected (false)
397    pub accepted: bool,
398}
399
400impl IterationStats {
401    /// Print table header in Ceres-style format
402    pub fn print_header() {
403        debug!(
404            "{:>4}  {:>13}  {:>13}  {:>13}  {:>13}  {:>11}  {:>11}  {:>7}  {:>11}  {:>13}  {:>6}",
405            "iter",
406            "cost",
407            "cost_change",
408            "|gradient|",
409            "|step|",
410            "tr_ratio",
411            "tr_radius",
412            "ls_iter",
413            "iter_time",
414            "total_time",
415            "status"
416        );
417    }
418
419    /// Print single iteration line in Ceres-style format with scientific notation
420    pub fn print_line(&self) {
421        let status = if self.iteration == 0 {
422            "-"
423        } else if self.accepted {
424            "✓"
425        } else {
426            "✗"
427        };
428
429        debug!(
430            "{:>4}  {:>13.6e}  {:>13.2e}  {:>13.2e}  {:>13.2e}  {:>11.2e}  {:>11.2e}  {:>7}  {:>9.2}ms  {:>11.2}ms  {:>6}",
431            self.iteration,
432            self.cost,
433            self.cost_change,
434            self.gradient_norm,
435            self.step_norm,
436            self.tr_ratio,
437            self.tr_radius,
438            self.ls_iter,
439            self.iter_time_ms,
440            self.total_time_ms,
441            status
442        );
443    }
444}
445
446/// Result of optimization state initialization, shared by all optimizers.
447pub struct InitializedState {
448    pub variables: HashMap<String, VariableEnum>,
449    pub variable_index_map: HashMap<String, usize>,
450    pub sorted_vars: Vec<String>,
451    pub symbolic_structure: Option<SymbolicStructure>,
452    pub total_dof: usize,
453    pub current_cost: f64,
454    pub initial_cost: f64,
455}
456
457/// Compute total parameter vector norm ||x|| across all variables.
458pub fn compute_parameter_norm(variables: &HashMap<String, VariableEnum>) -> f64 {
459    variables
460        .values()
461        .map(|v| {
462            let vec = v.to_vector();
463            vec.norm_squared()
464        })
465        .sum::<f64>()
466        .sqrt()
467}
468
469/// Create Jacobi scaling diagonal matrix from Jacobian column norms.
470///
471/// The scaling factor for each column is `1 / (1 + ||col||)`, which normalizes
472/// the columns to improve conditioning of the linear system.
473pub fn create_jacobi_scaling(
474    jacobian: &SparseColMat<usize, f64>,
475) -> Result<SparseColMat<usize, f64>, OptimizerError> {
476    let cols = jacobian.ncols();
477    let jacobi_scaling_vec: Vec<Triplet<usize, usize, f64>> = (0..cols)
478        .map(|c| {
479            let col_norm_squared: f64 = jacobian
480                .triplet_iter()
481                .filter(|t| t.col == c)
482                .map(|t| t.val * t.val)
483                .sum();
484            let col_norm = col_norm_squared.sqrt();
485            let scaling = 1.0 / (1.0 + col_norm);
486            Triplet::new(c, c, scaling)
487        })
488        .collect();
489
490    SparseColMat::try_new_from_triplets(cols, cols, &jacobi_scaling_vec)
491        .map_err(|e| OptimizerError::JacobiScalingCreation(e.to_string()).log_with_source(e))
492}
493
494/// Process Jacobian by applying Jacobi scaling (created on first iteration).
495///
496/// On `iteration == 0`, creates the scaling matrix and stores it. On subsequent
497/// iterations, reuses the cached scaling.
498pub fn process_jacobian(
499    jacobian: &SparseColMat<usize, f64>,
500    jacobi_scaling: &mut Option<SparseColMat<usize, f64>>,
501    iteration: usize,
502) -> Result<SparseColMat<usize, f64>, OptimizerError> {
503    if iteration == 0 {
504        let scaling = create_jacobi_scaling(jacobian)?;
505        *jacobi_scaling = Some(scaling);
506    }
507    let scaling = jacobi_scaling
508        .as_ref()
509        .ok_or_else(|| OptimizerError::JacobiScalingNotInitialized.log())?;
510    Ok(jacobian * scaling)
511}
512
513/// Initialize optimization state from problem and initial parameters.
514///
515/// This is the common initialization sequence used by all optimizers:
516/// 1. Create variables from initial values
517/// 2. Build variable-to-column index mapping
518/// 3. Build symbolic sparsity structure for Jacobian (sparse mode only)
519/// 4. Compute initial cost
520///
521/// The assembly mode is determined by `problem.jacobian_mode`.
522pub fn initialize_optimization_state(
523    problem: &Problem,
524    initial_params: &HashMap<String, (ManifoldType, DVector<f64>)>,
525) -> OptimizerResult<InitializedState> {
526    let variables = problem.initialize_variables(initial_params);
527
528    let mut variable_index_map = HashMap::new();
529    let mut col_offset = 0;
530    let mut sorted_vars: Vec<String> = variables.keys().cloned().collect();
531    sorted_vars.sort();
532
533    for var_name in &sorted_vars {
534        variable_index_map.insert(var_name.clone(), col_offset);
535        col_offset += variables[var_name].get_size();
536    }
537
538    let total_dof = col_offset;
539
540    let symbolic_structure = match problem.jacobian_mode {
541        JacobianMode::Sparse => Some(crate::linearizer::cpu::sparse::build_symbolic_structure(
542            problem,
543            &variables,
544            &variable_index_map,
545            total_dof,
546        )?),
547        JacobianMode::Dense => None,
548    };
549
550    let residual = problem.compute_residual_sparse(&variables)?;
551    let current_cost = compute_cost(&residual);
552    let initial_cost = current_cost;
553
554    Ok(InitializedState {
555        variables,
556        variable_index_map,
557        sorted_vars,
558        symbolic_structure,
559        total_dof,
560        current_cost,
561        initial_cost,
562    })
563}
564
565/// Parameters for convergence checking, shared across optimizers.
566pub struct ConvergenceParams {
567    pub iteration: usize,
568    pub current_cost: f64,
569    pub new_cost: f64,
570    pub parameter_norm: f64,
571    pub parameter_update_norm: f64,
572    pub gradient_norm: f64,
573    pub elapsed: Duration,
574    pub step_accepted: bool,
575    // Config values
576    pub max_iterations: usize,
577    pub gradient_tolerance: f64,
578    pub parameter_tolerance: f64,
579    pub cost_tolerance: f64,
580    pub min_cost_threshold: Option<f64>,
581    pub timeout: Option<Duration>,
582    /// Trust region radius (LM damping or DogLeg radius). None for GN.
583    pub trust_region_radius: Option<f64>,
584    /// Minimum trust region radius threshold. None for GN.
585    pub min_trust_region_radius: Option<f64>,
586}
587
588/// Check convergence criteria common to all optimizers.
589///
590/// Returns `Some(status)` if a termination criterion is met, `None` otherwise.
591pub fn check_convergence(params: &ConvergenceParams) -> Option<OptimizationStatus> {
592    // CRITICAL SAFETY CHECKS (perform first)
593
594    // Invalid Numerical Values (NaN/Inf)
595    if !params.new_cost.is_finite()
596        || !params.parameter_update_norm.is_finite()
597        || !params.gradient_norm.is_finite()
598    {
599        return Some(OptimizationStatus::InvalidNumericalValues);
600    }
601
602    // Timeout
603    if let Some(timeout) = params.timeout {
604        if params.elapsed >= timeout {
605            return Some(OptimizationStatus::Timeout);
606        }
607    }
608
609    // Maximum Iterations
610    if params.iteration >= params.max_iterations {
611        return Some(OptimizationStatus::MaxIterationsReached);
612    }
613
614    // CONVERGENCE CRITERIA (only check after accepted steps)
615    if !params.step_accepted {
616        return None;
617    }
618
619    // Gradient Norm (First-Order Optimality)
620    if params.gradient_norm < params.gradient_tolerance {
621        return Some(OptimizationStatus::GradientToleranceReached);
622    }
623
624    // Parameter and cost criteria (only after first iteration)
625    if params.iteration > 0 {
626        // Parameter Change Tolerance (xtol)
627        let relative_step_tolerance =
628            params.parameter_tolerance * (params.parameter_norm + params.parameter_tolerance);
629        if params.parameter_update_norm <= relative_step_tolerance {
630            return Some(OptimizationStatus::ParameterToleranceReached);
631        }
632
633        // Function Value Change Tolerance (ftol)
634        let cost_change = (params.current_cost - params.new_cost).abs();
635        let relative_cost_change = cost_change / params.current_cost.max(1e-10);
636        if relative_cost_change < params.cost_tolerance {
637            return Some(OptimizationStatus::CostToleranceReached);
638        }
639    }
640
641    // Objective Function Cutoff (optional early stopping)
642    if let Some(min_cost) = params.min_cost_threshold {
643        if params.new_cost < min_cost {
644            return Some(OptimizationStatus::MinCostThresholdReached);
645        }
646    }
647
648    // Trust Region Radius (LM and DogLeg only)
649    if let (Some(radius), Some(min_radius)) =
650        (params.trust_region_radius, params.min_trust_region_radius)
651    {
652        if radius < min_radius {
653            return Some(OptimizationStatus::TrustRegionRadiusTooSmall);
654        }
655    }
656
657    None
658}
659
660/// Compute step quality ratio (actual vs predicted reduction).
661///
662/// Used by Levenberg-Marquardt and Dog Leg optimizers to evaluate
663/// whether a proposed step improved the objective function as predicted
664/// by the local quadratic model.
665///
666/// Returns `ρ = actual_reduction / predicted_reduction`, handling
667/// near-zero predicted reduction gracefully.
668pub fn compute_step_quality(current_cost: f64, new_cost: f64, predicted_reduction: f64) -> f64 {
669    let actual_reduction = current_cost - new_cost;
670    if predicted_reduction.abs() < 1e-15 {
671        if actual_reduction > 0.0 { 1.0 } else { 0.0 }
672    } else {
673        actual_reduction / predicted_reduction
674    }
675}
676
677/// Create the appropriate linear solver based on configuration.
678///
679/// Used by Gauss-Newton and Dog Leg optimizers. Levenberg-Marquardt has its own
680/// solver creation logic due to special Schur complement adapter requirements.
681pub fn create_linear_solver(
682    solver_type: &linalg::LinearSolverType,
683) -> Box<dyn LinearSolver<SparseMode>> {
684    match solver_type {
685        linalg::LinearSolverType::SparseCholesky => Box::new(SparseCholeskySolver::new()),
686        linalg::LinearSolverType::SparseQR => Box::new(SparseQRSolver::new()),
687        _ => {
688            // SparseSchurComplement requires special handling; DenseCholesky/DenseQR are
689            // dispatched via the dense path in each optimizer — all fall back to Cholesky here.
690            Box::new(SparseCholeskySolver::new())
691        }
692    }
693}
694
695/// Notify observers with current optimization state (sparse path).
696///
697/// This is the common observer notification pattern used by all three optimizers.
698#[allow(clippy::too_many_arguments)]
699pub fn notify_observers(
700    observers: &mut OptObserverVec,
701    variables: &HashMap<String, VariableEnum>,
702    iteration: usize,
703    cost: f64,
704    gradient_norm: f64,
705    damping: Option<f64>,
706    step_norm: f64,
707    step_quality: Option<f64>,
708    linear_solver: &dyn LinearSolver<SparseMode>,
709) {
710    observers.set_iteration_metrics(cost, gradient_norm, damping, step_norm, step_quality);
711
712    if !observers.is_empty() {
713        if let (Some(hessian), Some(gradient)) =
714            (linear_solver.get_hessian(), linear_solver.get_gradient())
715        {
716            observers.set_matrix_data(Some(hessian.clone()), Some(gradient.clone()));
717        }
718    }
719
720    observers.notify(variables, iteration);
721}
722
723/// Notify observers with current optimization state (generic path).
724///
725/// For dense mode, the Hessian is converted to sparse for observer compatibility.
726/// This is acceptable since observers are for visualization/debugging, not the hot path.
727#[allow(clippy::too_many_arguments)]
728pub fn notify_observers_generic<M: AssemblyBackend>(
729    observers: &mut OptObserverVec,
730    variables: &HashMap<String, VariableEnum>,
731    iteration: usize,
732    cost: f64,
733    gradient_norm: f64,
734    damping: Option<f64>,
735    step_norm: f64,
736    step_quality: Option<f64>,
737    _linear_solver: &dyn LinearSolver<M>,
738) {
739    observers.set_iteration_metrics(cost, gradient_norm, damping, step_norm, step_quality);
740    // Skip matrix data for generic path since observers expect sparse Hessian.
741    // Observer matrix visualization is optional and only used for debugging.
742    observers.notify(variables, iteration);
743}
744
745/// Process Jacobian with Jacobi scaling (generic over assembly mode).
746///
747/// On `iteration == 0`, computes the scaling factors and stores them.
748/// On subsequent iterations, reuses the cached scaling.
749pub fn process_jacobian_generic<M: AssemblyBackend>(
750    jacobian: &M::Jacobian,
751    jacobi_scaling: &mut Option<Vec<f64>>,
752    iteration: usize,
753) -> Result<M::Jacobian, OptimizerError> {
754    if iteration == 0 {
755        let norms = M::compute_column_norms(jacobian);
756        let scaling: Vec<f64> = norms.iter().map(|n| 1.0 / (1.0 + n)).collect();
757        *jacobi_scaling = Some(scaling);
758    }
759    let scaling = jacobi_scaling
760        .as_ref()
761        .ok_or_else(|| OptimizerError::JacobiScalingNotInitialized.log())?;
762    Ok(M::apply_column_scaling(jacobian, scaling))
763}
764
765/// Build a SolverResult from common optimization loop outputs.
766///
767/// All three optimizers construct SolverResult identically at convergence.
768#[allow(clippy::too_many_arguments)]
769pub fn build_solver_result(
770    status: OptimizationStatus,
771    iterations: usize,
772    state: InitializedState,
773    elapsed: Duration,
774    final_gradient_norm: f64,
775    final_parameter_update_norm: f64,
776    cost_evaluations: usize,
777    jacobian_evaluations: usize,
778    covariances: Option<HashMap<String, Mat<f64>>>,
779) -> SolverResult<HashMap<String, VariableEnum>> {
780    SolverResult {
781        status,
782        iterations,
783        initial_cost: state.initial_cost,
784        final_cost: state.current_cost,
785        parameters: state.variables.into_iter().collect(),
786        elapsed_time: elapsed,
787        convergence_info: Some(ConvergenceInfo {
788            final_gradient_norm,
789            final_parameter_update_norm,
790            cost_evaluations,
791            jacobian_evaluations,
792        }),
793        covariances,
794    }
795}
796
797/// Unified summary statistics for all optimizer types.
798///
799/// Replaces the separate `LevenbergMarquardtSummary`, `GaussNewtonSummary`,
800/// and `DogLegSummary` structs with a single type that handles algorithm-specific
801/// fields via `Option`.
802#[derive(Debug, Clone)]
803pub struct OptimizerSummary {
804    /// Name of the optimizer algorithm
805    pub optimizer_name: &'static str,
806    /// Initial cost value
807    pub initial_cost: f64,
808    /// Final cost value
809    pub final_cost: f64,
810    /// Total number of iterations performed
811    pub iterations: usize,
812    /// Number of successful steps (None for GN which always accepts)
813    pub successful_steps: Option<usize>,
814    /// Number of unsuccessful steps (None for GN which always accepts)
815    pub unsuccessful_steps: Option<usize>,
816    /// Average cost reduction per iteration
817    pub average_cost_reduction: f64,
818    /// Maximum gradient norm encountered
819    pub max_gradient_norm: f64,
820    /// Final gradient norm
821    pub final_gradient_norm: f64,
822    /// Maximum parameter update norm
823    pub max_parameter_update_norm: f64,
824    /// Final parameter update norm
825    pub final_parameter_update_norm: f64,
826    /// Total time elapsed
827    pub total_time: Duration,
828    /// Average time per iteration
829    pub average_time_per_iteration: Duration,
830    /// Detailed per-iteration statistics history
831    pub iteration_history: Vec<IterationStats>,
832    /// Convergence status
833    pub convergence_status: OptimizationStatus,
834    /// Final damping parameter (LM only)
835    pub final_damping: Option<f64>,
836    /// Final trust region radius (DL only)
837    pub final_trust_region_radius: Option<f64>,
838    /// Step quality ratio (LM only)
839    pub rho: Option<f64>,
840}
841
842impl Display for OptimizerSummary {
843    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
844        let converged = matches!(
845            self.convergence_status,
846            OptimizationStatus::Converged
847                | OptimizationStatus::CostToleranceReached
848                | OptimizationStatus::GradientToleranceReached
849                | OptimizationStatus::ParameterToleranceReached
850        );
851
852        writeln!(f, "{} Final Result", self.optimizer_name)?;
853
854        if converged {
855            writeln!(f, "CONVERGED ({:?})", self.convergence_status)?;
856        } else {
857            writeln!(f, "DIVERGED ({:?})", self.convergence_status)?;
858        }
859
860        writeln!(f)?;
861        writeln!(f, "Cost:")?;
862        writeln!(f, "  Initial:   {:.6e}", self.initial_cost)?;
863        writeln!(f, "  Final:     {:.6e}", self.final_cost)?;
864        writeln!(
865            f,
866            "  Reduction: {:.6e} ({:.2}%)",
867            self.initial_cost - self.final_cost,
868            100.0 * (self.initial_cost - self.final_cost) / self.initial_cost.max(1e-12)
869        )?;
870        writeln!(f)?;
871        writeln!(f, "Iterations:")?;
872        writeln!(f, "  Total:              {}", self.iterations)?;
873        if let (Some(successful), Some(unsuccessful)) =
874            (self.successful_steps, self.unsuccessful_steps)
875        {
876            writeln!(
877                f,
878                "  Successful steps:   {} ({:.1}%)",
879                successful,
880                100.0 * successful as f64 / self.iterations.max(1) as f64
881            )?;
882            writeln!(
883                f,
884                "  Unsuccessful steps: {} ({:.1}%)",
885                unsuccessful,
886                100.0 * unsuccessful as f64 / self.iterations.max(1) as f64
887            )?;
888        }
889        if let Some(radius) = self.final_trust_region_radius {
890            writeln!(f)?;
891            writeln!(f, "Trust Region:")?;
892            writeln!(f, "  Final radius: {:.6e}", radius)?;
893        }
894        writeln!(f)?;
895        writeln!(f, "Gradient:")?;
896        writeln!(f, "  Max norm:   {:.2e}", self.max_gradient_norm)?;
897        writeln!(f, "  Final norm: {:.2e}", self.final_gradient_norm)?;
898        writeln!(f)?;
899        writeln!(f, "Parameter Update:")?;
900        writeln!(f, "  Max norm:   {:.2e}", self.max_parameter_update_norm)?;
901        writeln!(f, "  Final norm: {:.2e}", self.final_parameter_update_norm)?;
902        writeln!(f)?;
903        writeln!(f, "Performance:")?;
904        writeln!(
905            f,
906            "  Total time:             {:.2}ms",
907            self.total_time.as_secs_f64() * 1000.0
908        )?;
909        writeln!(
910            f,
911            "  Average per iteration:  {:.2}ms",
912            self.average_time_per_iteration.as_secs_f64() * 1000.0
913        )?;
914
915        Ok(())
916    }
917}
918
919/// Create an OptimizerSummary from common optimization loop outputs.
920#[allow(clippy::too_many_arguments)]
921pub fn create_optimizer_summary(
922    optimizer_name: &'static str,
923    initial_cost: f64,
924    final_cost: f64,
925    iterations: usize,
926    successful_steps: Option<usize>,
927    unsuccessful_steps: Option<usize>,
928    max_gradient_norm: f64,
929    final_gradient_norm: f64,
930    max_parameter_update_norm: f64,
931    final_parameter_update_norm: f64,
932    total_cost_reduction: f64,
933    total_time: Duration,
934    iteration_history: Vec<IterationStats>,
935    convergence_status: OptimizationStatus,
936    final_damping: Option<f64>,
937    final_trust_region_radius: Option<f64>,
938    rho: Option<f64>,
939) -> OptimizerSummary {
940    OptimizerSummary {
941        optimizer_name,
942        initial_cost,
943        final_cost,
944        iterations,
945        successful_steps,
946        unsuccessful_steps,
947        average_cost_reduction: if iterations > 0 {
948            total_cost_reduction / iterations as f64
949        } else {
950            0.0
951        },
952        max_gradient_norm,
953        final_gradient_norm,
954        max_parameter_update_norm,
955        final_parameter_update_norm,
956        total_time,
957        average_time_per_iteration: if iterations > 0 {
958            total_time / iterations as u32
959        } else {
960            Duration::from_secs(0)
961        },
962        iteration_history,
963        convergence_status,
964        final_damping,
965        final_trust_region_radius,
966        rho,
967    }
968}
969
970#[cfg(test)]
971mod tests {
972    use super::*;
973    use crate::core::problem::VariableEnum;
974    use crate::core::variable::Variable;
975    use crate::factors::Factor;
976    use crate::linalg::JacobianMode;
977    use apex_manifolds::ManifoldType;
978    use apex_manifolds::rn::Rn;
979    use faer::Mat;
980    use faer::sparse::{SparseColMat, Triplet};
981    use nalgebra::{DMatrix, DVector, dvector};
982    use std::collections::HashMap;
983    use std::time::Duration;
984
985    type TestResult = Result<(), Box<dyn std::error::Error>>;
986
987    // -------------------------------------------------------------------------
988    // compute_cost
989    // -------------------------------------------------------------------------
990
991    #[test]
992    fn test_compute_cost_known_value() {
993        // ||[1, 2]||² * 0.5 = (1 + 4) * 0.5 = 2.5
994        let r = Mat::from_fn(2, 1, |i, _| (i + 1) as f64);
995        let cost = compute_cost(&r);
996        assert!((cost - 2.5).abs() < 1e-12, "expected 2.5, got {cost}");
997    }
998
999    #[test]
1000    fn test_compute_cost_zero_residual() {
1001        let r = Mat::zeros(3, 1);
1002        assert_eq!(compute_cost(&r), 0.0);
1003    }
1004
1005    // -------------------------------------------------------------------------
1006    // compute_step_quality
1007    // -------------------------------------------------------------------------
1008
1009    #[test]
1010    fn test_compute_step_quality_normal() {
1011        // actual = 1.0-0.0 = 1.0, predicted = 2.0 → rho = 0.5
1012        let rho = compute_step_quality(1.0, 0.0, 2.0);
1013        assert!((rho - 0.5).abs() < 1e-12);
1014    }
1015
1016    #[test]
1017    fn test_compute_step_quality_zero_predicted_positive_actual() {
1018        // predicted ≈ 0, actual > 0 → 1.0
1019        let rho = compute_step_quality(2.0, 1.0, 0.0);
1020        assert_eq!(rho, 1.0);
1021    }
1022
1023    #[test]
1024    fn test_compute_step_quality_zero_predicted_nonpositive_actual() {
1025        // predicted ≈ 0, actual ≤ 0 → 0.0
1026        let rho = compute_step_quality(1.0, 2.0, 0.0); // actual = -1.0
1027        assert_eq!(rho, 0.0);
1028    }
1029
1030    #[test]
1031    fn test_compute_step_quality_negative_reduction() {
1032        // cost increased: actual = 1.0 - 2.0 = -1.0, predicted = 1.0 → -1.0
1033        let rho = compute_step_quality(1.0, 2.0, 1.0);
1034        assert!((rho - (-1.0)).abs() < 1e-12);
1035    }
1036
1037    // -------------------------------------------------------------------------
1038    // create_jacobi_scaling
1039    // -------------------------------------------------------------------------
1040
1041    fn make_identity_jacobian(n: usize) -> SparseColMat<usize, f64> {
1042        let triplets: Vec<Triplet<usize, usize, f64>> =
1043            (0..n).map(|i| Triplet::new(i, i, 1.0)).collect();
1044        SparseColMat::try_new_from_triplets(n, n, &triplets).unwrap_or_else(|_| {
1045            let empty: Vec<Triplet<usize, usize, f64>> = vec![];
1046            SparseColMat::try_new_from_triplets(0, 0, &empty)
1047                .unwrap_or_else(|_| panic!("failed to create empty matrix"))
1048        })
1049    }
1050
1051    #[test]
1052    fn test_create_jacobi_scaling_identity_jacobian() -> TestResult {
1053        // For identity Jacobian each column has norm 1.0 → scaling = 1/(1+1) = 0.5
1054        let jac = make_identity_jacobian(3);
1055        let scaling = create_jacobi_scaling(&jac)?;
1056        for i in 0..3 {
1057            let val = scaling.get(i, i).copied().unwrap_or(0.0);
1058            assert!(
1059                (val - 0.5).abs() < 1e-12,
1060                "col {i}: expected 0.5, got {val}"
1061            );
1062        }
1063        Ok(())
1064    }
1065
1066    #[test]
1067    fn test_create_jacobi_scaling_zero_column() -> TestResult {
1068        // A zero column has norm 0 → scaling = 1/(1+0) = 1.0
1069        let triplets = vec![Triplet::new(0_usize, 0_usize, 1.0_f64)];
1070        let jac = SparseColMat::try_new_from_triplets(2, 2, &triplets)?;
1071        let scaling = create_jacobi_scaling(&jac)?;
1072        // col 0: norm=1 → 0.5; col 1: norm=0 → 1.0
1073        let s0 = scaling.get(0, 0).copied().unwrap_or(0.0);
1074        let s1 = scaling.get(1, 1).copied().unwrap_or(0.0);
1075        assert!((s0 - 0.5).abs() < 1e-12);
1076        assert!((s1 - 1.0).abs() < 1e-12);
1077        Ok(())
1078    }
1079
1080    // -------------------------------------------------------------------------
1081    // process_jacobian
1082    // -------------------------------------------------------------------------
1083
1084    #[test]
1085    fn test_process_jacobian_creates_at_iter0() -> TestResult {
1086        let jac = make_identity_jacobian(2);
1087        let mut cache: Option<SparseColMat<usize, f64>> = None;
1088        let scaled = process_jacobian(&jac, &mut cache, 0)?;
1089        assert!(cache.is_some(), "scaling should be cached after iter 0");
1090        // Each diagonal entry should be scaled by 0.5
1091        let s = scaled.get(0, 0).copied().unwrap_or(0.0);
1092        assert!((s - 0.5).abs() < 1e-12);
1093        Ok(())
1094    }
1095
1096    #[test]
1097    fn test_process_jacobian_reuses_at_iter1() -> TestResult {
1098        let jac = make_identity_jacobian(2);
1099        let mut cache: Option<SparseColMat<usize, f64>> = None;
1100        // build cache at iter 0
1101        process_jacobian(&jac, &mut cache, 0)?;
1102        // now use cached at iter 1
1103        let scaled = process_jacobian(&jac, &mut cache, 1)?;
1104        let s = scaled.get(0, 0).copied().unwrap_or(0.0);
1105        assert!((s - 0.5).abs() < 1e-12);
1106        Ok(())
1107    }
1108
1109    #[test]
1110    fn test_process_jacobian_error_at_iter1_without_init() {
1111        let jac = make_identity_jacobian(2);
1112        let mut cache: Option<SparseColMat<usize, f64>> = None;
1113        // skip iter 0 — should error
1114        let result = process_jacobian(&jac, &mut cache, 1);
1115        assert!(result.is_err(), "should fail without prior iter=0 call");
1116    }
1117
1118    // -------------------------------------------------------------------------
1119    // compute_parameter_norm
1120    // -------------------------------------------------------------------------
1121
1122    #[test]
1123    fn test_compute_parameter_norm_two_variables() {
1124        let mut vars: HashMap<String, VariableEnum> = HashMap::new();
1125        vars.insert(
1126            "a".into(),
1127            VariableEnum::Rn(Variable::new(Rn::new(dvector![3.0]))),
1128        );
1129        vars.insert(
1130            "b".into(),
1131            VariableEnum::Rn(Variable::new(Rn::new(dvector![4.0]))),
1132        );
1133        let norm = compute_parameter_norm(&vars);
1134        // sqrt(3² + 4²) = 5.0
1135        assert!((norm - 5.0).abs() < 1e-12, "expected 5.0, got {norm}");
1136    }
1137
1138    #[test]
1139    fn test_compute_parameter_norm_empty() {
1140        let vars: HashMap<String, VariableEnum> = HashMap::new();
1141        assert_eq!(compute_parameter_norm(&vars), 0.0);
1142    }
1143
1144    // -------------------------------------------------------------------------
1145    // apply_parameter_step / apply_negative_parameter_step
1146    // -------------------------------------------------------------------------
1147
1148    #[test]
1149    fn test_apply_parameter_step_advances_variable() {
1150        let mut vars: HashMap<String, VariableEnum> = HashMap::new();
1151        vars.insert(
1152            "x".into(),
1153            VariableEnum::Rn(Variable::new(Rn::new(dvector![0.0]))),
1154        );
1155        let order = vec!["x".to_string()];
1156        let step = Mat::from_fn(1, 1, |_, _| 3.0);
1157        let norm = apply_parameter_step(&mut vars, step.as_ref(), &order);
1158        assert!((norm - 3.0).abs() < 1e-12);
1159        let val = vars["x"].to_vector()[0];
1160        assert!((val - 3.0).abs() < 1e-12, "expected 3.0, got {val}");
1161    }
1162
1163    #[test]
1164    fn test_apply_negative_parameter_step_reverts() {
1165        let mut vars: HashMap<String, VariableEnum> = HashMap::new();
1166        vars.insert(
1167            "x".into(),
1168            VariableEnum::Rn(Variable::new(Rn::new(dvector![5.0]))),
1169        );
1170        let order = vec!["x".to_string()];
1171        let step = Mat::from_fn(1, 1, |_, _| 2.0);
1172        // apply +2 first
1173        apply_parameter_step(&mut vars, step.as_ref(), &order);
1174        assert!((vars["x"].to_vector()[0] - 7.0).abs() < 1e-12);
1175        // then revert with -2
1176        apply_negative_parameter_step(&mut vars, step.as_ref(), &order);
1177        assert!((vars["x"].to_vector()[0] - 5.0).abs() < 1e-12);
1178    }
1179
1180    // -------------------------------------------------------------------------
1181    // check_convergence — all branches
1182    // -------------------------------------------------------------------------
1183
1184    fn base_params() -> ConvergenceParams {
1185        ConvergenceParams {
1186            iteration: 1,
1187            current_cost: 1.0,
1188            new_cost: 0.9,
1189            parameter_norm: 1.0,
1190            parameter_update_norm: 1e-3,
1191            gradient_norm: 1e-3,
1192            elapsed: Duration::from_millis(10),
1193            step_accepted: true,
1194            max_iterations: 100,
1195            gradient_tolerance: 1e-10,
1196            parameter_tolerance: 1e-10,
1197            cost_tolerance: 1e-10,
1198            min_cost_threshold: None,
1199            timeout: None,
1200            trust_region_radius: None,
1201            min_trust_region_radius: None,
1202        }
1203    }
1204
1205    #[test]
1206    fn test_check_convergence_no_trigger() {
1207        assert!(check_convergence(&base_params()).is_none());
1208    }
1209
1210    #[test]
1211    fn test_check_convergence_nan_cost() {
1212        let mut p = base_params();
1213        p.new_cost = f64::NAN;
1214        assert_eq!(
1215            check_convergence(&p),
1216            Some(OptimizationStatus::InvalidNumericalValues)
1217        );
1218    }
1219
1220    #[test]
1221    fn test_check_convergence_inf_gradient() {
1222        let mut p = base_params();
1223        p.gradient_norm = f64::INFINITY;
1224        assert_eq!(
1225            check_convergence(&p),
1226            Some(OptimizationStatus::InvalidNumericalValues)
1227        );
1228    }
1229
1230    #[test]
1231    fn test_check_convergence_timeout() {
1232        let mut p = base_params();
1233        p.timeout = Some(Duration::from_millis(5));
1234        p.elapsed = Duration::from_millis(10);
1235        assert_eq!(check_convergence(&p), Some(OptimizationStatus::Timeout));
1236    }
1237
1238    #[test]
1239    fn test_check_convergence_max_iterations() {
1240        let mut p = base_params();
1241        p.iteration = 100;
1242        p.max_iterations = 100;
1243        assert_eq!(
1244            check_convergence(&p),
1245            Some(OptimizationStatus::MaxIterationsReached)
1246        );
1247    }
1248
1249    #[test]
1250    fn test_check_convergence_gradient_tolerance() {
1251        let mut p = base_params();
1252        p.step_accepted = true;
1253        p.gradient_norm = 1e-12;
1254        p.gradient_tolerance = 1e-10;
1255        assert_eq!(
1256            check_convergence(&p),
1257            Some(OptimizationStatus::GradientToleranceReached)
1258        );
1259    }
1260
1261    #[test]
1262    fn test_check_convergence_parameter_tolerance() {
1263        let mut p = base_params();
1264        p.step_accepted = true;
1265        p.gradient_norm = 1.0; // above tolerance
1266        p.parameter_update_norm = 1e-20;
1267        p.parameter_tolerance = 1e-8;
1268        p.parameter_norm = 1.0;
1269        assert_eq!(
1270            check_convergence(&p),
1271            Some(OptimizationStatus::ParameterToleranceReached)
1272        );
1273    }
1274
1275    #[test]
1276    fn test_check_convergence_cost_tolerance() {
1277        let mut p = base_params();
1278        p.step_accepted = true;
1279        p.gradient_norm = 1.0; // above
1280        p.parameter_update_norm = 1.0; // above
1281        p.current_cost = 1.0;
1282        p.new_cost = 1.0 - 1e-15; // nearly no change
1283        p.cost_tolerance = 1e-10;
1284        assert_eq!(
1285            check_convergence(&p),
1286            Some(OptimizationStatus::CostToleranceReached)
1287        );
1288    }
1289
1290    #[test]
1291    fn test_check_convergence_min_cost_threshold() {
1292        let mut p = base_params();
1293        p.step_accepted = true;
1294        p.gradient_norm = 1.0;
1295        p.parameter_update_norm = 1.0;
1296        p.current_cost = 1.0;
1297        p.new_cost = 1.0 - 0.5; // big change — cost tol not triggered
1298        p.cost_tolerance = 1e-10;
1299        p.min_cost_threshold = Some(1.0); // new_cost=0.5 < 1.0 → trigger
1300        assert_eq!(
1301            check_convergence(&p),
1302            Some(OptimizationStatus::MinCostThresholdReached)
1303        );
1304    }
1305
1306    #[test]
1307    fn test_check_convergence_trust_region_too_small() {
1308        let mut p = base_params();
1309        p.step_accepted = true;
1310        p.gradient_norm = 1.0;
1311        p.parameter_update_norm = 1.0;
1312        p.current_cost = 1.0;
1313        p.new_cost = 0.5;
1314        p.cost_tolerance = 1e-10;
1315        p.trust_region_radius = Some(1e-40);
1316        p.min_trust_region_radius = Some(1e-32);
1317        assert_eq!(
1318            check_convergence(&p),
1319            Some(OptimizationStatus::TrustRegionRadiusTooSmall)
1320        );
1321    }
1322
1323    #[test]
1324    fn test_check_convergence_step_not_accepted_skips_criteria() {
1325        // With step_accepted=false, gradient/parameter/cost tol should NOT fire
1326        let mut p = base_params();
1327        p.step_accepted = false;
1328        p.gradient_norm = 0.0; // would trigger gradient tol if accepted
1329        p.parameter_update_norm = 0.0;
1330        p.new_cost = 0.0;
1331        assert!(check_convergence(&p).is_none());
1332    }
1333
1334    // -------------------------------------------------------------------------
1335    // create_linear_solver
1336    // -------------------------------------------------------------------------
1337
1338    #[test]
1339    fn test_create_linear_solver_cholesky() {
1340        let solver = create_linear_solver(&crate::linalg::LinearSolverType::SparseCholesky);
1341        // just verify it's constructable and callable without panic
1342        let _ = solver.get_hessian();
1343    }
1344
1345    #[test]
1346    fn test_create_linear_solver_qr() {
1347        let solver = create_linear_solver(&crate::linalg::LinearSolverType::SparseQR);
1348        let _ = solver.get_hessian();
1349    }
1350
1351    #[test]
1352    fn test_create_linear_solver_fallback_for_schur() {
1353        // SparseSchurComplement is special; falls back to Cholesky in create_linear_solver
1354        let solver = create_linear_solver(&crate::linalg::LinearSolverType::SparseSchurComplement);
1355        let _ = solver.get_hessian();
1356    }
1357
1358    // -------------------------------------------------------------------------
1359    // Display impls
1360    // -------------------------------------------------------------------------
1361
1362    #[test]
1363    fn test_optimizer_type_display() {
1364        assert_eq!(
1365            format!("{}", OptimizerType::LevenbergMarquardt),
1366            "Levenberg-Marquardt"
1367        );
1368        assert_eq!(format!("{}", OptimizerType::GaussNewton), "Gauss-Newton");
1369        assert_eq!(format!("{}", OptimizerType::DogLeg), "Dog Leg");
1370    }
1371
1372    #[test]
1373    fn test_optimization_status_display() {
1374        assert_eq!(format!("{}", OptimizationStatus::Converged), "Converged");
1375        assert_eq!(
1376            format!("{}", OptimizationStatus::MaxIterationsReached),
1377            "Maximum iterations reached"
1378        );
1379        assert_eq!(format!("{}", OptimizationStatus::Timeout), "Timeout");
1380        assert_eq!(
1381            format!("{}", OptimizationStatus::InvalidNumericalValues),
1382            "Invalid numerical values (NaN/Inf) detected"
1383        );
1384        assert!(format!("{}", OptimizationStatus::Failed("oops".into())).contains("oops"));
1385    }
1386
1387    #[test]
1388    fn test_optimizer_error_variants() {
1389        let e1 = OptimizerError::TrustRegionFailure {
1390            radius: 1e-40,
1391            min_radius: 1e-32,
1392        };
1393        assert!(e1.to_string().contains("Trust region radius"));
1394
1395        let e2 = OptimizerError::DampingFailure {
1396            damping: 1e13,
1397            max_damping: 1e12,
1398        };
1399        assert!(e2.to_string().contains("Damping parameter"));
1400
1401        let e3 = OptimizerError::CostIncrease {
1402            old_cost: 1.0,
1403            new_cost: 2.0,
1404        };
1405        assert!(e3.to_string().contains("Cost increased"));
1406
1407        let e4 = OptimizerError::LinearSolveFailed("singular".into());
1408        assert!(e4.to_string().contains("singular"));
1409
1410        let e5 = OptimizerError::EmptyProblem;
1411        assert!(e5.to_string().contains("no variables"));
1412
1413        let e6 = OptimizerError::NoResidualBlocks;
1414        assert!(e6.to_string().contains("residual blocks"));
1415    }
1416
1417    // -------------------------------------------------------------------------
1418    // IterationStats print (smoke tests — no panic)
1419    // -------------------------------------------------------------------------
1420
1421    #[test]
1422    fn test_iteration_stats_print_header_no_panic() {
1423        IterationStats::print_header();
1424    }
1425
1426    #[test]
1427    fn test_iteration_stats_print_line_no_panic() {
1428        let stats = IterationStats {
1429            iteration: 1,
1430            cost: 1.5,
1431            cost_change: -0.5,
1432            gradient_norm: 1e-3,
1433            step_norm: 1e-4,
1434            tr_ratio: 0.8,
1435            tr_radius: 1e3,
1436            ls_iter: 0,
1437            iter_time_ms: 2.5,
1438            total_time_ms: 10.0,
1439            accepted: true,
1440        };
1441        stats.print_line();
1442    }
1443
1444    // -------------------------------------------------------------------------
1445    // build_solver_result
1446    // -------------------------------------------------------------------------
1447
1448    #[test]
1449    fn test_build_solver_result_fields() -> TestResult {
1450        let mut variables: HashMap<String, VariableEnum> = HashMap::new();
1451        variables.insert(
1452            "x".into(),
1453            VariableEnum::Rn(Variable::new(Rn::new(dvector![3.0]))),
1454        );
1455        let state = InitializedState {
1456            variables,
1457            variable_index_map: HashMap::new(),
1458            sorted_vars: vec!["x".to_string()],
1459            symbolic_structure: None,
1460            total_dof: 1,
1461            current_cost: 0.1,
1462            initial_cost: 5.0,
1463        };
1464        let result = build_solver_result(
1465            OptimizationStatus::CostToleranceReached,
1466            10,
1467            state,
1468            Duration::from_millis(50),
1469            1e-5,
1470            1e-6,
1471            15,
1472            10,
1473            None,
1474        );
1475        assert_eq!(result.status, OptimizationStatus::CostToleranceReached);
1476        assert_eq!(result.iterations, 10);
1477        assert!((result.initial_cost - 5.0).abs() < 1e-12);
1478        assert!((result.final_cost - 0.1).abs() < 1e-12);
1479        let ci = result
1480            .convergence_info
1481            .as_ref()
1482            .ok_or("convergence_info is None")?;
1483        assert_eq!(ci.cost_evaluations, 15);
1484        assert_eq!(ci.jacobian_evaluations, 10);
1485        Ok(())
1486    }
1487
1488    // -------------------------------------------------------------------------
1489    // create_optimizer_summary
1490    // -------------------------------------------------------------------------
1491
1492    #[test]
1493    fn test_create_optimizer_summary_averages() {
1494        let summary = create_optimizer_summary(
1495            "TestOptimizer",
1496            10.0,
1497            1.0,
1498            4,
1499            Some(3),
1500            Some(1),
1501            2.0,
1502            0.1,
1503            3.0,
1504            0.05,
1505            9.0, // total_cost_reduction
1506            Duration::from_millis(400),
1507            vec![],
1508            OptimizationStatus::CostToleranceReached,
1509            Some(1e-3),
1510            None,
1511            Some(0.8),
1512        );
1513        // average_cost_reduction = 9.0 / 4 = 2.25
1514        assert!((summary.average_cost_reduction - 2.25).abs() < 1e-10);
1515        // average_time_per_iteration = 400ms / 4 = 100ms
1516        assert_eq!(
1517            summary.average_time_per_iteration,
1518            Duration::from_millis(100)
1519        );
1520        assert_eq!(summary.optimizer_name, "TestOptimizer");
1521        assert_eq!(summary.successful_steps, Some(3));
1522    }
1523
1524    #[test]
1525    fn test_create_optimizer_summary_zero_iterations() {
1526        let summary = create_optimizer_summary(
1527            "Test",
1528            1.0,
1529            1.0,
1530            0, // zero iterations
1531            None,
1532            None,
1533            0.0,
1534            0.0,
1535            0.0,
1536            0.0,
1537            0.0,
1538            Duration::from_secs(0),
1539            vec![],
1540            OptimizationStatus::MaxIterationsReached,
1541            None,
1542            None,
1543            None,
1544        );
1545        assert_eq!(summary.average_cost_reduction, 0.0);
1546        assert_eq!(summary.average_time_per_iteration, Duration::from_secs(0));
1547    }
1548
1549    // -------------------------------------------------------------------------
1550    // Simple Factor for integration tests in mod.rs
1551    // -------------------------------------------------------------------------
1552
1553    /// Linear factor: r = x - target, J = [[1.0]]
1554    struct LinearFactor {
1555        target: f64,
1556    }
1557
1558    impl Factor for LinearFactor {
1559        fn linearize(
1560            &self,
1561            params: &[DVector<f64>],
1562            compute_jacobian: bool,
1563        ) -> (DVector<f64>, Option<DMatrix<f64>>) {
1564            let residual = dvector![params[0][0] - self.target];
1565            let jacobian = if compute_jacobian {
1566                Some(DMatrix::from_element(1, 1, 1.0))
1567            } else {
1568                None
1569            };
1570            (residual, jacobian)
1571        }
1572
1573        fn get_dimension(&self) -> usize {
1574            1
1575        }
1576    }
1577
1578    // -------------------------------------------------------------------------
1579    // initialize_optimization_state (smoke test)
1580    // -------------------------------------------------------------------------
1581
1582    #[test]
1583    fn test_initialize_optimization_state() -> TestResult {
1584        use crate::core::problem::Problem;
1585
1586        let mut problem = Problem::new(JacobianMode::Sparse);
1587        let mut initial_values: HashMap<String, (ManifoldType, DVector<f64>)> = HashMap::new();
1588        initial_values.insert("x".to_string(), (ManifoldType::RN, dvector![5.0]));
1589        problem.add_residual_block(&["x"], Box::new(LinearFactor { target: 0.0 }), None);
1590
1591        let state = initialize_optimization_state(&problem, &initial_values)?;
1592        assert_eq!(state.total_dof, 1);
1593        assert!(state.initial_cost > 0.0);
1594        assert!(state.sorted_vars.contains(&"x".to_string()));
1595        Ok(())
1596    }
1597}