๐ฆ Apex Solver
A high-performance Rust-based nonlinear least squares optimization library designed for computer vision applications including bundle adjustment, SLAM, and pose graph optimization. Built with focus on zero-cost abstractions, memory safety, and mathematical correctness.
Apex Solver is a comprehensive optimization library that bridges the gap between theoretical robotics and practical implementation. It provides manifold-aware optimization for Lie groups commonly used in computer vision, multiple optimization algorithms with unified interfaces, flexible linear algebra backends supporting both sparse Cholesky and QR decompositions, and industry-standard file format support for seamless integration with existing workflows.
Key Features (v1.3.0)
- ๐ท Bundle Adjustment with Camera Intrinsic Optimization: Simultaneous optimization of camera poses, 3D landmarks, and camera intrinsics (8 camera models via apex-camera-models crate) apex-camera-models
- ๐ง Explicit & Implicit Schur Complement Solvers: Memory-efficient matrix-free PCG for large-scale problems (10,000+ cameras) alongside traditional explicit formulation
- ๐ก๏ธ 15 Robust Loss Functions: Comprehensive outlier rejection (Huber, Cauchy, Tukey, Welsch, Barron, and more)
- ๐ Manifold-Aware: Full Lie group support (SE2, SE3, SO2, SO3, SE_2(3), SGal(3), Sim(3), Rn) with analytic Jacobians apex-manifolds
- ๐ Three Optimization Algorithms: Levenberg-Marquardt, Gauss-Newton, and Dog Leg with unified interface
- ๐ Prior Factors & Fixed Variables: Anchor poses with known values and constrain specific parameter indices
- ๐ Uncertainty Quantification: Covariance estimation for both Cholesky and QR solvers
- ๐จ Real-time Visualization: Integrated Rerun support for live debugging of optimization progress
- ๐ I/O: Read and write G2O, Toro, BAL format files for seamless integration with SLAM ecosystems apex-io
- โก High Performance: Sparse linear algebra with persistent symbolic factorization
- โ Production-Grade: Comprehensive error handling, structured tracing, integration test suite
๐ Quick Start
use HashMap;
use Problem;
use ;
use ;
use ;
use dvector;
Result:
Status: CostToleranceReached
Initial cost: 1.280e+05
Final cost: 2.130e+01
Iterations: 5
๐๏ธ Architecture
The workspace root is the apex-solver crate. Sub-crates for manifolds, I/O, and camera models live in crates/:
apex-solver/ # workspace root = apex-solver crate
โโโ src/
โ โโโ core/ # Problem formulation, factors, residuals
โ โโโ factors/ # Factor implementations (projection, between, prior)
โ โโโ optimizer/ # LM, GN, Dog Leg algorithms
โ โโโ linalg/ # Cholesky, QR, Explicit/Implicit Schur
โ โโโ observers/ # Optimization observers and callbacks
โโโ bin/ # Executable binaries
โโโ benches/ # Benchmarks
โโโ examples/ # Example programs
โโโ tests/ # Integration tests
โโโ doc/ # Extended documentation
โโโ crates/
โโโ apex-manifolds/ # Lie groups: SE2, SE3, SO2, SO3, SE_2(3), SGal(3), Sim(3), Rn
โโโ apex-io/ # File I/O: G2O, TORO, BAL formats
โโโ apex-camera-models/ # 8 camera projection models
Core Modules (in src/):
core/: Optimization problem definitions, residual blocks, robust loss functions, and variable managementoptimizer/: Three optimization algorithms (Levenberg-Marquardt with adaptive damping, Gauss-Newton, Dog Leg trust region) with real-time visualization supportlinalg/: Linear algebra backends including sparse Cholesky decomposition, QR factorization, explicit Schur complement, and implicit Schur complement (matrix-free PCG)observers/: Optimization observers and callbacks (Rerun visualization, custom hooks)
Workspace Sub-crates (in crates/):
apex-manifolds: Lie group implementations (SE2, SE3, SO2, SO3, SE_2(3), SGal(3), Sim(3), Rn) with analytic Jacobiansapex-io: File format parsers for G2O, TORO, and BAL formatsapex-camera-models: Camera projection models with analytic Jacobians (10 models)
Low-level Dependencies:
faer/nalgebra: High-performance linear algebra backends
๐ Datasets
Datasets are downloaded on demand using the built-in download_datasets tool in the apex-io crate. No Git LFS required.
# List all available datasets and selection numbers
# Download benchmark datasets (all odometry g2o + largest from each BA dataset)
# Download all odometry g2o datasets (2D + 3D)
# Interactive mode (prompts for selection)
Datasets are saved to data/odometry/ (g2o files) and data/bundle_adjustment/ (BAL format).
Available datasets:
- Pose Graph SE2 (2D):
M3500,mit,city10000,ring - Pose Graph SE3 (3D):
sphere2500,parking-garage,torus3D,cubicle - Bundle Adjustment (UW BAL):
ladybug,trafalgar,dubrovnik,venice,final
๐ฆ Workspace Crates
Apex Solver is organized as a Cargo workspace with specialized sub-crates that can be used independently:
| Crate | Description | Docs |
|---|---|---|
| apex-manifolds | Lie group manifolds (SE2, SE3, SO2, SO3, SE_2(3), SGal(3), Sim(3), Rn) with analytic Jacobians | README |
| apex-camera-models | 10 camera projection models for bundle adjustment and SLAM | README |
| apex-io | File I/O utilities for G2O, TORO, and BAL formats | README |
Using sub-crates independently:
[]
= "0.2.0"
[]
= "0.2.0"
[]
= "0.2.0"
๐ Performance Benchmarks
Detailed benchmark tables comparing apex-solver against Ceres, GTSAM, g2o, factrs, and tiny-solver on 8 pose-graph datasets (SE2/SE3) and 4 BAL bundle-adjustment datasets.
โ Full performance benchmarks
๐ Examples
Usage examples covering pose graph optimization, custom factor implementation, and self-calibration bundle adjustment.
โ Full examples
๐งฎ Technical Implementation
Robust Loss Functions
15 robust loss functions for handling outliers in optimization:
- L2Loss: Standard least squares (no outliers)
- L1Loss: Linear growth (light outliers)
- HuberLoss: Quadratic near zero, linear after threshold (moderate outliers)
- CauchyLoss: Logarithmic growth (heavy outliers)
- FairLoss, GemanMcClureLoss, WelschLoss, TukeyBiweightLoss, AndrewsWaveLoss: Various robustness profiles
- RamsayEaLoss: Asymmetric outliers
- TrimmedMeanLoss: Ignores worst residuals
- LpNormLoss: Generalized Lp norm
- BarronGeneralLoss, AdaptiveBarronLoss: Adaptive robustness
- TDistributionLoss: Statistical outliers
Usage:
use HuberLoss;
let loss = new; // 95% efficiency threshold
problem.add_residual_block;
Optimization Algorithms
Levenberg-Marquardt (Recommended)
- Adaptive damping between gradient descent and Gauss-Newton
- Robust convergence from poor initial estimates
- Supports covariance estimation for uncertainty quantification
- 9 comprehensive termination criteria (gradient norm, cost change, trust region radius, etc.)
Gauss-Newton
- Fast convergence near solution
- Minimal memory requirements
- Best for well-initialized problems
Dog Leg Trust Region
- Combines steepest descent and Gauss-Newton
- Global convergence guarantees
- Adaptive trust region management
Linear Algebra Backends
Four sparse linear solvers for different use cases:
- Sparse Cholesky: Direct factorization of J^T J + ฮปI - fast, moderate memory, best for well-conditioned problems
- Sparse QR: QR factorization of Jacobian - robust for rank-deficient systems, slightly slower
- Explicit Schur Complement: Constructs reduced camera matrix S = B - E Cโปยน Eแต explicitly in memory - most accurate for bundle adjustment, moderate memory usage
- Implicit Schur Complement: Matrix-free PCG solver computing only Sยทx products - memory-efficient for large-scale problems (10,000+ cameras), highly scalable
Configure via LinearSolverType in optimizer config:
config.with_linear_solver_type // For bundle adjustment
config.with_linear_solver_type // For very large BA
๐จ Interactive Visualization
Real-time optimization debugging with integrated Rerun visualization using the observer pattern:
use ;
let config = new
.with_max_iterations;
let mut solver = with_config;
// Add Rerun visualization observer (requires `visualization` feature)
let result = solver.optimize?;
Visualized Metrics:
- Time series: Cost, gradient norm, damping (ฮป), step quality (ฯ), step norm
- Matrix visualizations: Hessian heat map, gradient vector
- 3D poses: SE3 camera frusta, SE2 2D points
Run Examples:
# Enable visualization feature and run
Note: The data files (e.g.,
sphere2500.g2o) must be downloaded first. See ๐ Datasets โ runcargo run --release -p apex-io --bin download_datasets -- --select 10to get all benchmark datasets.
Zero overhead when disabled (feature-gated).
๐ง Learning Resources
Computer Vision Background
- Multiple View Geometry (Hartley & Zisserman) - Mathematical foundations
- Visual SLAM algorithms (Durrant-Whyte & Bailey) - Probabilistic robotics
- g2o documentation - Reference C++ implementation
Lie Group Theory
- A micro Lie theory (Solร et al.) - Practical introduction
- manif library - C++ reference we follow
- State Estimation for Robotics (Barfoot) - SO(3) and SE(3)
Optimization Theory
- Numerical Optimization (Nocedal & Wright) - Standard reference
- Trust Region Methods - Dog Leg theory
- Ceres Solver Tutorial - Practical guide
๐ Acknowledgments
Apex Solver draws inspiration and reference implementations from:
- Ceres Solver - Google's C++ optimization library
- g2o - General framework for graph optimization
- GTSAM - Georgia Tech Smoothing and Mapping library
- tiny-solver - Lightweight nonlinear least squares solver
- factrs - Rust factor graph optimization library
- faer - High-performance linear algebra library for Rust
- manif - C++ Lie theory library (for manifold conventions)
- nalgebra - Geometry and linear algebra primitives
๐ License
Licensed under the Apache License, Version 2.0. See LICENSE for details.