vision-calibration-linear
Linear and closed-form initialization solvers for camera and rig calibration.
This crate provides deterministic, minimal-dependency implementations of classic
computer vision algorithms. These are intended as starting points for
non-linear refinement in vision-calibration-optim or vision-calibration-pipeline.
Algorithms
| Category | Algorithms |
|---|---|
| Homography | Normalized DLT, RANSAC wrapper |
| Intrinsics | Zhang's method, iterative with distortion |
| Pose (PnP) | DLT, P3P, EPnP, RANSAC variants |
| Epipolar | 8-point, 7-point fundamental; 5-point essential |
| Triangulation | Linear DLT |
| Rig | Multi-camera extrinsics initialization |
| Hand-eye | Tsai-Lenz (AX=XB) |
| Laserline | Multi-view laser plane fitting |
Expected Accuracy
These solvers are initialization-grade. Regression tests validate:
| Algorithm | Accuracy | Notes |
|---|---|---|
| Zhang intrinsics | fx/fy ~5%, cx/cy ~8px | No distortion |
| Iterative intrinsics | fx/fy ~10-40% | With distortion |
| Planar pose | R <0.05 rad, t <5 units | Square = 30 units |
| Fundamental (8-pt) | Scaled error <0.07 | |
| Essential (5-pt) | Residuals ~3x GT | |
| Triangulation | p90 error <2 units | Ground-truth poses |
Thresholds are intentionally loose for stable initialization.
Coordinate Conventions
- Poses:
T_C_W(transform from world/board into camera frame) - Fundamental matrix: Accepts pixel coordinates
- Essential matrix: Expects normalized coordinates (after K^-1)
- PnP solvers: Accept pixel coordinates + intrinsics (normalize internally)
Usage Examples
Homography Estimation
use dlt_homography;
use Pt2;
let world = vec!;
let image = vec!;
let h = dlt_homography?;
println!;
# Ok::
PnP (Perspective-n-Point)
use ;
use ;
let points_3d = vec!;
let points_2d = vec!;
let k = identity; // Intrinsics matrix
// Direct DLT (all points)
let pose = pnp_dlt?;
// RANSAC for outlier rejection
let = pnp_ransac?;
# Ok::
Iterative Intrinsics (with Distortion)
use ;
let views: = /* prepare views */;
let opts = default;
let result = estimate?;
println!;
println!;
# Ok::
Hand-Eye Calibration
use ;
use Iso3;
let base_se3_gripper: = /* T_B_G from robot controller */;
// EyeInHand: estimate gripper->camera from target->camera poses (T_T_C).
let target_se3_camera: = /* e.g. invert camera_se3_target (T_C_T) */;
let min_angle_deg = 5.0;
let gripper_se3_camera = estimate_handeye_dlt?;
// EyeToHand: estimate gripper->target from camera->target poses (T_C_T).
let camera_se3_target: = /* from PnP / planar pose (T_C_T) */;
let gripper_se3_target = estimate_gripper_se3_target_dlt?;
# Ok::
Laserline Plane Fitting
use ;
let views: = /* views with laser pixels */;
let camera = /* calibrated camera */;
// Multi-view fitting breaks single-view collinearity
let estimate = from_views?;
println!;
# Ok::
Modules
| Module | Description |
|---|---|
homography |
DLT homography + RANSAC |
zhang_intrinsics |
Zhang's closed-form intrinsics |
iterative_intrinsics |
Iterative K + distortion estimation |
distortion_fit |
Distortion from homography residuals |
planar_pose |
Pose from homography + K |
pnp |
DLT, P3P, EPnP, RANSAC |
epipolar |
Fundamental/essential matrices |
triangulation |
Linear triangulation |
extrinsics |
Multi-camera rig initialization |
handeye |
Tsai-Lenz hand-eye |
laserline |
Laser plane estimation |
See Also
- vision-calibration-core: Math types, camera models, RANSAC engine
- vision-calibration-optim: Non-linear refinement
- vision-calibration-pipeline: High-level calibration pipelines
- Book: Linear Calibration