vision_calibration/lib.rs
1//! High-level entry crate for the `calibration-rs` camera calibration library.
2//!
3//! This crate provides a unified API for camera calibration workflows:
4//! - Single-camera intrinsics calibration (Zhang's method with distortion)
5//! - Single-camera intrinsics calibration with Scheimpflug tilt
6//! - Single-camera hand-eye calibration (camera on robot arm)
7//! - Multi-camera rig extrinsics calibration
8//! - Multi-camera rig + hand-eye calibration
9//!
10//! # Quick Start
11//!
12//! ```no_run
13//! # fn main() -> anyhow::Result<()> {
14//! # let dataset = unimplemented!();
15//! use vision_calibration::prelude::*;
16//! use vision_calibration::planar_intrinsics::{step_init, step_optimize};
17//!
18//! // Create calibration session
19//! let mut session = CalibrationSession::<PlanarIntrinsicsProblem>::new();
20//! session.set_input(dataset)?;
21//!
22//! // Option 1: Step-by-step (recommended for inspection)
23//! step_init(&mut session, None)?;
24//! step_optimize(&mut session, None)?;
25//!
26//! // Option 2: Pipeline function (convenience)
27//! // run_planar_intrinsics(&mut session)?;
28//!
29//! // Export results
30//! let result = session.export()?;
31//! # Ok(())
32//! # }
33//! ```
34//!
35//! # Module Organization
36//!
37//! ## High-Level Calibration Workflows
38//!
39//! - [`session`] - Session framework (`CalibrationSession`, `ProblemType`)
40//! - [`planar_intrinsics`] - Single-camera intrinsics (Zhang's method)
41//! - [`single_cam_handeye`] - Single camera + hand-eye calibration
42//! - [`rig_extrinsics`] - Multi-camera rig extrinsics
43//! - [`rig_handeye`] - Multi-camera rig + hand-eye
44//! - [`laserline_device`] - Single camera + laser plane device
45//! - [`scheimpflug_intrinsics`] - Single-camera planar intrinsics with Scheimpflug tilt
46//!
47//! ## Foundation Crates (Advanced Users)
48//!
49//! - [`core`] - Math types, camera models, RANSAC primitives
50//! - [`linear`] - Closed-form initialization algorithms
51//! - [`optim`] - Non-linear least-squares optimization
52//! - [`synthetic`] - Synthetic data generation for testing
53//!
54//! # Session API
55//!
56//! All calibration workflows use the [`session::CalibrationSession`] state container.
57//! Each problem type has its own set of step functions — see the table below
58//! and the per-module documentation for details.
59//!
60//! The common pattern is:
61//! 1. Create a session for the problem type
62//! 2. Set input data with `set_input`
63//! 3. Optionally configure with `update_config`
64//! 4. Run the problem-specific step functions (or a convenience `run_calibration`)
65//! 5. Export results with `export`
66//!
67//! # Available Problem Types
68//!
69//! | Problem Type | Input | Steps |
70//! |--------------|-------|-------|
71//! | [`PlanarIntrinsicsProblem`](planar_intrinsics) | `PlanarDataset` | `step_init` → `step_optimize` |
72//! | [`SingleCamHandeyeProblem`](single_cam_handeye) | `SingleCamHandeyeInput` | `step_intrinsics_init` → `step_intrinsics_optimize` → `step_handeye_init` → `step_handeye_optimize` |
73//! | [`RigExtrinsicsProblem`](rig_extrinsics) | `RigExtrinsicsInput` | `step_intrinsics_init_all` → `step_intrinsics_optimize_all` → `step_rig_init` → `step_rig_optimize` |
74//! | [`RigHandeyeProblem`](rig_handeye) | `RigHandeyeInput` | `step_intrinsics_init_all` → `step_intrinsics_optimize_all` → `step_rig_init` → `step_rig_optimize` → `step_handeye_init` → `step_handeye_optimize` |
75//! | [`LaserlineDeviceProblem`](laserline_device) | `LaserlineDeviceInput` | `step_init` → `step_optimize` |
76//! | [`ScheimpflugIntrinsicsProblem`](scheimpflug_intrinsics) | `PlanarDataset` | `step_init` → `step_optimize` |
77
78#![deny(missing_docs)]
79
80/// Typed error returned by all public calibration step functions.
81pub use vision_calibration_pipeline::Error;
82
83/// Single-camera planar intrinsics with Scheimpflug/tilted sensor refinement.
84///
85/// This high-level helper mirrors planar intrinsics calibration, but optimizes a
86/// Brown-Conrady camera together with two Scheimpflug tilt parameters.
87pub mod scheimpflug_intrinsics {
88 pub use vision_calibration_pipeline::scheimpflug_intrinsics::{
89 IntrinsicsInitOptions, IntrinsicsOptimizeOptions, ScheimpflugFixMask,
90 ScheimpflugIntrinsicsConfig, ScheimpflugIntrinsicsExport, ScheimpflugIntrinsicsInput,
91 ScheimpflugIntrinsicsParams, ScheimpflugIntrinsicsProblem, ScheimpflugIntrinsicsResult,
92 ScheimpflugIntrinsicsState, run_calibration, step_init, step_optimize,
93 };
94}
95
96// ═══════════════════════════════════════════════════════════════════════════════
97// Session Framework
98// ═══════════════════════════════════════════════════════════════════════════════
99
100/// Session framework for structured calibration workflows.
101///
102/// Provides mutable state containers, step functions, and JSON checkpointing.
103pub mod session {
104 pub use vision_calibration_pipeline::session::{
105 CalibrationSession, ExportRecord, InvalidationPolicy, LogEntry, ProblemType,
106 SessionMetadata,
107 };
108}
109
110// ═══════════════════════════════════════════════════════════════════════════════
111// Problem-Specific Modules
112// ═══════════════════════════════════════════════════════════════════════════════
113
114/// Planar intrinsics calibration (Zhang's method with Brown-Conrady distortion).
115///
116/// # Steps
117/// 1. `step_init` - Zhang's method with iterative distortion estimation
118/// 2. `step_optimize` - Non-linear refinement
119/// 3. `step_filter` (optional) - Remove outliers by reprojection error
120///
121/// # Example
122/// ```no_run
123/// # fn main() -> anyhow::Result<()> {
124/// # let dataset = unimplemented!();
125/// use vision_calibration::prelude::*;
126/// use vision_calibration::planar_intrinsics::{step_init, step_optimize, run_calibration};
127///
128/// let mut session = CalibrationSession::<PlanarIntrinsicsProblem>::new();
129/// session.set_input(dataset)?;
130/// run_calibration(&mut session)?;
131/// let result = session.export()?;
132/// # Ok(())
133/// # }
134/// ```
135pub mod planar_intrinsics {
136 pub use vision_calibration_pipeline::planar_intrinsics::{
137 // Step options
138 FilterOptions,
139 IntrinsicsInitOptions,
140 IntrinsicsOptimizeOptions,
141 // Problem type and config
142 PlanarIntrinsicsConfig,
143 // Re-exports from vision-calibration-optim
144 PlanarIntrinsicsEstimate,
145 PlanarIntrinsicsExport,
146 PlanarIntrinsicsParams,
147 PlanarIntrinsicsProblem,
148 PlanarIntrinsicsSolveOptions,
149 PlanarState,
150 // Step functions
151 run_calibration,
152 run_calibration_with_filtering,
153 step_filter,
154 step_init,
155 step_optimize,
156 };
157}
158
159/// Single-camera hand-eye calibration (intrinsics + hand-eye transform).
160///
161/// For calibrating a camera mounted on a robot arm.
162///
163/// # Steps
164/// 1. `step_intrinsics_init` - Zhang's method
165/// 2. `step_intrinsics_optimize` - Non-linear intrinsics refinement
166/// 3. `step_handeye_init` - Tsai-Lenz linear estimation
167/// 4. `step_handeye_optimize` - Bundle adjustment
168///
169/// # Example
170/// ```no_run
171/// # fn main() -> anyhow::Result<()> {
172/// # let input = unimplemented!();
173/// use vision_calibration::prelude::*;
174/// use vision_calibration::single_cam_handeye::{
175/// run_calibration, SingleCamHandeyeInput, SingleCamHandeyeProblem
176/// };
177///
178/// let mut session = CalibrationSession::<SingleCamHandeyeProblem>::new();
179/// session.set_input(input)?;
180/// run_calibration(&mut session)?;
181/// let result = session.export()?;
182/// # Ok(())
183/// # }
184/// ```
185pub mod single_cam_handeye {
186 pub use vision_calibration_pipeline::single_cam_handeye::{
187 // Step options
188 HandeyeInitOptions,
189 // Problem type and config
190 HandeyeMeta,
191 HandeyeOptimizeOptions,
192 IntrinsicsInitOptions,
193 IntrinsicsOptimizeOptions,
194 SingleCamHandeyeConfig,
195 SingleCamHandeyeExport,
196 SingleCamHandeyeInput,
197 SingleCamHandeyeProblem,
198 SingleCamHandeyeState,
199 SingleCamHandeyeView,
200 // Step functions
201 run_calibration,
202 step_handeye_init,
203 step_handeye_optimize,
204 step_intrinsics_init,
205 step_intrinsics_optimize,
206 };
207}
208
209/// Single laserline device calibration (camera + laser plane).
210///
211/// # Steps
212/// 1. `step_init` - Iterative intrinsics + linear laser plane init
213/// 2. `step_optimize` - Joint bundle adjustment
214///
215/// # Example
216/// ```no_run
217/// # fn main() -> anyhow::Result<()> {
218/// # let input = unimplemented!();
219/// use vision_calibration::prelude::*;
220/// use vision_calibration::laserline_device::{
221/// run_calibration, LaserlineDeviceInput, LaserlineDeviceProblem
222/// };
223///
224/// let mut session = CalibrationSession::<LaserlineDeviceProblem>::new();
225/// session.set_input(input)?;
226/// run_calibration(&mut session, None)?;
227/// let result = session.export()?;
228/// # Ok(())
229/// # }
230/// ```
231pub mod laserline_device {
232 pub use vision_calibration_pipeline::laserline_device::{
233 DeviceInitOptions, DeviceOptimizeOptions, LaserlineDeviceConfig, LaserlineDeviceExport,
234 LaserlineDeviceInitConfig, LaserlineDeviceInput, LaserlineDeviceOptimizeConfig,
235 LaserlineDeviceOutput, LaserlineDeviceProblem, LaserlineDeviceSolverConfig,
236 LaserlineDeviceState, run_calibration, step_init, step_optimize,
237 };
238}
239
240/// Multi-camera rig extrinsics calibration.
241///
242/// For calibrating a multi-camera rig, estimating per-camera intrinsics
243/// and camera-to-rig transforms.
244///
245/// # Steps
246/// 1. `step_intrinsics_init_all` - Per-camera Zhang's method
247/// 2. `step_intrinsics_optimize_all` - Per-camera non-linear refinement
248/// 3. `step_rig_init` - Linear estimation of camera-to-rig transforms
249/// 4. `step_rig_optimize` - Joint bundle adjustment
250///
251/// # Example
252/// ```no_run
253/// # fn main() -> anyhow::Result<()> {
254/// # let input = unimplemented!();
255/// use vision_calibration::prelude::*;
256/// use vision_calibration::rig_extrinsics::{
257/// run_calibration, RigExtrinsicsInput, RigExtrinsicsProblem
258/// };
259///
260/// let mut session = CalibrationSession::<RigExtrinsicsProblem>::new();
261/// session.set_input(input)?;
262/// run_calibration(&mut session)?;
263/// let result = session.export()?;
264/// # Ok(())
265/// # }
266/// ```
267pub mod rig_extrinsics {
268 pub use vision_calibration_pipeline::rig_extrinsics::{
269 // Step options
270 IntrinsicsInitOptions,
271 IntrinsicsOptimizeOptions,
272 // Problem type and config
273 RigExtrinsicsConfig,
274 RigExtrinsicsExport,
275 RigExtrinsicsInput,
276 RigExtrinsicsProblem,
277 RigExtrinsicsState,
278 RigOptimizeOptions,
279 // Step functions
280 run_calibration,
281 step_intrinsics_init_all,
282 step_intrinsics_optimize_all,
283 step_rig_init,
284 step_rig_optimize,
285 };
286}
287
288/// Multi-camera rig hand-eye calibration.
289///
290/// For calibrating a multi-camera rig mounted on a robot arm, including
291/// per-camera intrinsics, rig extrinsics, and hand-eye transform.
292///
293/// # Steps (6 total)
294/// 1. `step_intrinsics_init_all` - Per-camera Zhang's method
295/// 2. `step_intrinsics_optimize_all` - Per-camera non-linear refinement
296/// 3. `step_rig_init` - Linear estimation of camera-to-rig transforms
297/// 4. `step_rig_optimize` - Rig bundle adjustment
298/// 5. `step_handeye_init` - Tsai-Lenz linear estimation
299/// 6. `step_handeye_optimize` - Hand-eye bundle adjustment
300///
301/// # Example
302/// ```no_run
303/// # fn main() -> anyhow::Result<()> {
304/// # let input = unimplemented!();
305/// use vision_calibration::prelude::*;
306/// use vision_calibration::rig_handeye::{run_calibration, RigHandeyeInput, RigHandeyeProblem};
307///
308/// let mut session = CalibrationSession::<RigHandeyeProblem>::new();
309/// session.set_input(input)?;
310/// run_calibration(&mut session)?;
311/// let result = session.export()?;
312/// # Ok(())
313/// # }
314/// ```
315pub mod rig_handeye {
316 pub use vision_calibration_pipeline::rig_handeye::{
317 // Step options
318 HandeyeInitOptions,
319 HandeyeOptimizeOptions,
320 IntrinsicsInitOptions,
321 IntrinsicsOptimizeOptions,
322 // Problem type and config
323 RigHandeyeBaConfig,
324 RigHandeyeConfig,
325 RigHandeyeExport,
326 RigHandeyeInitConfig,
327 RigHandeyeInput,
328 RigHandeyeIntrinsicsConfig,
329 RigHandeyeProblem,
330 RigHandeyeRigConfig,
331 RigHandeyeSolverConfig,
332 RigHandeyeState,
333 RigOptimizeOptions,
334 // Step functions
335 run_calibration,
336 step_handeye_init,
337 step_handeye_optimize,
338 step_intrinsics_init_all,
339 step_intrinsics_optimize_all,
340 step_rig_init,
341 step_rig_optimize,
342 };
343}
344
345// ═══════════════════════════════════════════════════════════════════════════════
346// Foundation Crates (Advanced Users)
347// ═══════════════════════════════════════════════════════════════════════════════
348
349/// Core math types, camera models, and RANSAC primitives.
350///
351/// Re-exports selected foundational types from `vision_calibration_core`.
352pub mod core {
353 pub use vision_calibration_core::{
354 BrownConrady5, Camera, CameraParams, CorrespondenceView, DistortionFixMask,
355 DistortionParams, FxFyCxCySkew, IdentitySensor, IntrinsicsFixMask, IntrinsicsParams, Iso3,
356 NoMeta, Pinhole, PinholeCamera, PlanarDataset, ProjectionParams, Pt2, Pt3, Real,
357 ReprojectionStats, RigDataset, RigView, RigViewObs, ScheimpflugParams, SensorModel,
358 SensorParams, Vec2, Vec3, View, make_pinhole_camera, pinhole_camera_params,
359 };
360}
361
362/// Closed-form initialization algorithms.
363///
364/// Includes homography estimation, Zhang's method, PnP solvers,
365/// triangulation, hand-eye solvers, and more.
366///
367/// Re-exports everything from `vision_calibration_linear`.
368pub mod linear {
369 pub use vision_calibration_linear::*;
370}
371
372/// Non-linear optimization with backend-agnostic IR.
373///
374/// Includes optimization problems, factors, and solver backends.
375///
376/// Re-exports everything from `vision_calibration_optim`.
377pub mod optim {
378 pub use vision_calibration_optim::*;
379}
380
381/// Deterministic synthetic data generation for testing.
382///
383/// Provides builders for creating synthetic calibration datasets.
384pub mod synthetic {
385 pub use vision_calibration_core::synthetic::*;
386}
387
388// ═══════════════════════════════════════════════════════════════════════════════
389// Prelude (Quick Start)
390// ═══════════════════════════════════════════════════════════════════════════════
391
392/// Minimal re-exports for planar "hello world" calibration.
393///
394/// ```no_run
395/// use vision_calibration::prelude::*;
396/// ```
397pub mod prelude {
398 /// Session framework for calibration workflows.
399 pub use vision_calibration_pipeline::session::CalibrationSession;
400
401 /// Planar intrinsics problem type for hello-world calibration.
402 pub use vision_calibration_pipeline::planar_intrinsics::PlanarIntrinsicsProblem;
403
404 /// Convenience planar calibration runner.
405 pub use vision_calibration_pipeline::planar_intrinsics::run_calibration as run_planar_intrinsics;
406
407 /// Core geometry and dataset types used in minimal planar workflows.
408 pub use vision_calibration_core::{
409 BrownConrady5, CorrespondenceView, FxFyCxCySkew, PlanarDataset, Pt2, Pt3, View,
410 make_pinhole_camera,
411 };
412}