Expand description
Non-linear optimization for camera calibration with automatic differentiation.
This crate provides a backend-agnostic optimization framework for camera calibration problems. The core design separates problem definition from solver implementation using an intermediate representation (IR) that can be compiled to different optimization backends.
§Architecture
The optimization pipeline has three stages:
- Problem Definition - Build a [
ir::ProblemIR] describing parameters, factors, and constraints - Backend Compilation - Translate IR into solver-specific problem (e.g., [
backend::TinySolverBackend]) - Optimization - Run solver and extract solution as domain types
Problem Builder → ProblemIR → Backend.compile() → Backend.solve() → Domain Result§Key Components
- [
ir] - Backend-agnostic intermediate representation for optimization problems - [
params] - Parameter block definitions (intrinsics, distortion, poses) - [
factors] - Residual functions with automatic differentiation support - [
backend] - Solver implementations (currently tiny-solver with Levenberg-Marquardt) - [
problems] - High-level calibration problem builders (planar intrinsics, etc.)
§Examples
§Basic Planar Intrinsics Calibration
use vision_calibration_core::{BrownConrady5, CorrespondenceView, DistortionFixMask, FxFyCxCySkew, Iso3, PlanarDataset, Pt2, Pt3, View};
use vision_calibration_optim::{
optimize_planar_intrinsics, BackendSolveOptions, PlanarIntrinsicsParams,
PlanarIntrinsicsSolveOptions, RobustLoss,
};
// 1. Prepare observations (world points + image detections)
let view = View::without_meta(CorrespondenceView::new(
vec![
Pt3::new(0.0, 0.0, 0.0),
Pt3::new(1.0, 0.0, 0.0),
Pt3::new(1.0, 1.0, 0.0),
Pt3::new(0.0, 1.0, 0.0),
],
vec![
Pt2::new(100.0, 100.0),
Pt2::new(200.0, 100.0),
Pt2::new(200.0, 200.0),
Pt2::new(100.0, 200.0),
],
)?);
let dataset = PlanarDataset::new(vec![view])?;
// 2. Initialize with linear method or prior calibration
let init = PlanarIntrinsicsParams::new_from_components(
FxFyCxCySkew {
fx: 800.0,
fy: 800.0,
cx: 640.0,
cy: 360.0,
skew: 0.0,
},
BrownConrady5 {
k1: 0.0,
k2: 0.0,
k3: 0.0,
p1: 0.0,
p2: 0.0,
iters: 8,
},
vec![Iso3::identity()],
)?;
// 3. Configure optimization
let opts = PlanarIntrinsicsSolveOptions {
robust_loss: RobustLoss::Huber { scale: 2.0 },
fix_distortion: DistortionFixMask { k3: true, ..Default::default() }, // Fix k3 to prevent overfitting
..Default::default()
};
// 4. Run optimization
let result = optimize_planar_intrinsics(&dataset, &init, opts, BackendSolveOptions::default())?;
println!("Calibrated camera: {:?}", result.params.camera);§Custom Problem with IR
§Feature Highlights
§Automatic Differentiation
All residual functions are generic over nalgebra::RealField, enabling automatic
differentiation via dual numbers. The [factors::reprojection_model] module provides
autodiff-compatible implementations of:
- Pinhole projection with SE3 poses
- Brown-Conrady distortion (k1, k2, k3, p1, p2)
- Weighted reprojection residuals
§Flexible Parameter Fixing
Use [ir::FixedMask] to selectively fix optimization variables:
let opts = PlanarIntrinsicsSolveOptions {
fix_intrinsics: IntrinsicsFixMask { fx: true, ..Default::default() }, // Fix focal length
fix_distortion: DistortionFixMask { p1: true, p2: true, ..Default::default() }, // Fix tangential distortion
..Default::default()
};§Robust Loss Functions
Handle outliers with M-estimators (ir::RobustLoss):
Huber- L2 near zero, L1 for outliersCauchy- Gradual outlier suppressionArctan- Bounded influence
§Performance Considerations
- Initialization: Always initialize with linear methods (the
vision-calibration-linearcrate) for faster convergence - Robust Loss: Use Huber with
scale ≈ 2.0for real data with corner detection noise - Distortion: Fix
k3by default unless calibrating wide-angle lenses - Manifolds: SE3/SO3 parameters use proper Lie group updates for stability
§Numerical Stability
The implementation uses several techniques for numerical robustness:
- Safe division with epsilon thresholds in projection
- Hartley normalization in linear initialization (via vision-calibration-linear)
- Manifold-aware parameter updates for rotations
- Sparse linear solvers for large problems
Modules§
- projection
- Minimal projection helpers shared by factors.
Structs§
- Backend
Solution - Solver output from a backend.
- Backend
Solve Options - Backend-agnostic solver options.
- Fixed
Mask - Fixed parameter mask for a block.
- Hand
EyeDataset - Dataset wrapper for hand-eye optimization.
- Hand
EyeEstimate - Result of hand-eye calibration.
- Hand
EyeParams - Initial values for hand-eye calibration.
- Hand
EyeSolve Options - Solve options for hand-eye calibration.
- Laser
Plane - Laser plane in camera frame: unit normal + signed distance.
- Laserline
Estimate - Result of laserline bundle adjustment.
- Laserline
Meta - Metadata for a laserline view (laser pixels + optional weights).
- Laserline
Params - Initial values for laserline bundle adjustment.
- Laserline
Solve Options - Solve options for laserline bundle adjustment.
- Laserline
Stats - Summary statistics for a laserline calibration result.
- Planar
Intrinsics Estimate - Output of planar intrinsics optimization.
- Planar
Intrinsics Params - Optimization result for planar intrinsics.
- Planar
Intrinsics Solve Options - Solve options specific to planar intrinsics.
- ProblemIR
- Backend-agnostic optimization problem representation.
- Residual
Block - Residual block definition in the IR.
- RigDataset
- Multi-view dataset for a camera rig.
- RigExtrinsics
Estimate - Output of rig extrinsics optimization.
- RigExtrinsics
Params - Result of rig extrinsics optimization.
- RigExtrinsics
Solve Options - Solve options for rig extrinsics.
- RigView
Obs - Multi-camera observations for one rig view/frame.
- Robot
Pose Meta - Per-view robot metadata required by hand-eye calibration.
- Scheimpflug
FixMask - Mask for Scheimpflug tilt parameters.
- Scheimpflug
Intrinsics Estimate - Optimization result for Scheimpflug intrinsics.
- Scheimpflug
Intrinsics Params - Initial/refined parameters for Scheimpflug intrinsics optimization.
- Scheimpflug
Intrinsics Solve Options - Solve options for Scheimpflug intrinsics optimization.
- Solve
Report - Summary of backend solve outcome.
- View
- Single-camera observation view with attached metadata.
Enums§
- Backend
Kind - Supported solver backends.
- Error
- Errors returned by public APIs in
vision-calibration-optim. - Factor
Kind - Backend-agnostic factor kinds.
- Hand
EyeMode - Hand-eye calibration mode.
- Laserline
Residual Type - Type of laser plane residual to use.
- Manifold
Kind - Supported manifold types for parameter blocks.
- Robust
Loss - Robust loss applied to a residual block.
Constants§
- DISTORTION_
DIM - Dimension of the Brown-Conrady distortion vector [k1, k2, k3, p1, p2].
- INTRINSICS_
DIM - Dimension of the intrinsics parameter vector [fx, fy, cx, cy].
Functions§
- compute_
laserline_ stats - Compute reprojection and laser residual statistics for a solution.
- iso3_
to_ se3_ dvec - Convert an
Iso3into a 7D SE(3) parameter vector[qx, qy, qz, qw, tx, ty, tz]. - optimize_
handeye - Optimize hand-eye calibration using specified backend.
- optimize_
laserline - Optimize laserline calibration with joint bundle adjustment.
- optimize_
planar_ intrinsics - Optimize planar intrinsics using the default tiny-solver backend.
- optimize_
rig_ extrinsics - Optimize rig extrinsics using specified backend.
- optimize_
scheimpflug_ intrinsics - Optimize Scheimpflug intrinsics using the default tiny-solver backend.
- pack_
distortion - Pack distortion into a dense parameter vector
[k1, k2, k3, p1, p2]. - pack_
intrinsics - Pack intrinsics into a dense parameter vector
[fx, fy, cx, cy]. - se3_
dvec_ to_ iso3 - Convert a 7D SE(3) vector
[qx, qy, qz, qw, tx, ty, tz]into anIso3. - solve_
with_ backend - Solve a problem using the selected backend.
Type Aliases§
- Laserline
Dataset - Dataset for laserline bundle adjustment.
- Laserline
View - A single view with calibration correspondences and laserline pixels.
- RigExtrinsics
Dataset - Dataset type for rig extrinsics optimization.