Kalibr represents every camera as a combination of a projection model and a distortion model, joined by a hyphen:Documentation Index
Fetch the complete documentation index at: https://mintlify.com/ethz-asl/kalibr/llms.txt
Use this file to discover all available pages before exploring further.
<projection>-<distortion>. You pass this string directly to --models when running kalibr_calibrate_cameras or kalibr_calibrate_rs_cameras. The projection component describes how 3D points map onto the image plane, and the distortion component describes the lens aberrations applied on top of that mapping. Choosing the right combination for your optics is important — a mismatch can cause the optimizer to diverge or produce inflated reprojection errors.
Model overview
| Model string | Projection | Distortion | Intrinsic parameters | Best for |
|---|---|---|---|---|
pinhole-radtan | Pinhole | Radial-tangential | fx, fy, cx, cy, k1, k2, p1, p2 | Standard lenses, narrow FOV |
pinhole-equi | Pinhole | Equidistant (fisheye) | fx, fy, cx, cy, k1, k2, k3, k4 | Wide-angle fisheye lenses |
pinhole-fov | Pinhole | Field-of-view | fx, fy, cx, cy, w | Fisheye with single-parameter distortion |
omni-none | Omnidirectional (Mei) | None | xi, fx, fy, cx, cy | Catadioptric / very wide FOV |
omni-radtan | Omnidirectional (Mei) | Radial-tangential | xi, fx, fy, cx, cy, k1, k2, p1, p2 | Catadioptric with lens distortion |
eucm-none | Extended Unified | None | alpha, beta, fx, fy, cx, cy | Wide-angle lenses up to ~180° |
ds-none | Double Sphere | None | xi, alpha, fx, fy, cx, cy | Fisheye and catadioptric lenses |
-rs suffix) are available for pinhole-radtan, pinhole-equi, and omni-radtan when using kalibr_calibrate_rs_cameras.
Detailed model descriptions
pinhole-radtan — pinhole with radial-tangential distortion
pinhole-radtan — pinhole with radial-tangential distortion
The classic pinhole-radtan combination is the most widely used model for cameras with a moderate field of view (typically under 120°). The pinhole projection maps a 3D point
(X, Y, Z) to image coordinates using focal lengths fx, fy and principal point cx, cy.Radial-tangential distortion (also called the Brown-Conrady model) corrects for barrel or pincushion distortion (k1, k2) and off-axis lens tilt (p1, p2).Parameters: [fx, fy, cx, cy, k1, k2, p1, p2] — 8 totalConstraints: None on distortion signs; both k1 and k2 can be negative (barrel) or positive (pincushion).Use when: Your camera has a field of view under ~120° and uses a standard (non-fisheye) lens. This is the default choice for most industrial and consumer cameras.Command-line model string: pinhole-radtanRolling shutter variant: pinhole-radtan-rspinhole-equi — pinhole with equidistant (fisheye) distortion
pinhole-equi — pinhole with equidistant (fisheye) distortion
The equidistant model (also called the Kannala-Brandt fisheye model) uses four distortion coefficients (
k1–k4) to handle wide-angle lenses where radial-tangential fails. The distortion is expressed as a polynomial of the angle of incidence, which remains well-behaved up to and beyond 180°.Parameters: [fx, fy, cx, cy, k1, k2, k3, k4] — 8 totalUse when: Your camera is equipped with a fisheye lens and has a field of view greater than ~120°. This is the recommended model for most wide-angle cameras used in robotics (e.g., GoPro, Realsense T265).Command-line model string: pinhole-equiRolling shutter variant: pinhole-equi-rspinhole-fov — pinhole with field-of-view distortion
pinhole-fov — pinhole with field-of-view distortion
The FOV model uses a single parameter
w (omega) to describe fisheye distortion. It is simpler than the equidistant model but can still handle moderately wide lenses. The omega parameter captures the ratio of the actual field of view to the ideal pinhole field of view.Parameters: [fx, fy, cx, cy, w] — 5 totalConstraints: w > 0. Values near 0 approach the pinhole model; larger values represent stronger distortion.Use when: You want a compact single-parameter fisheye model and do not require the accuracy of the four-coefficient equidistant model.Command-line model string: pinhole-fovomni-none — omnidirectional (Mei) camera without distortion
omni-none — omnidirectional (Mei) camera without distortion
The omnidirectional model due to Mei and Rives projects points via a unit sphere before applying a perspective projection. The parameter
xi (xi) controls the position of the projection center on the optical axis; xi = 0 recovers the standard pinhole, while larger values model catadioptric (mirror-based) cameras.Parameters: [xi, fx, fy, cx, cy] — 5 totalConstraints: xi >= 0Use when: You have a catadioptric (mirror + camera) system or an extreme wide-angle lens approaching a full hemisphere, and the lens aberrations are negligible.Command-line model string: omni-noneomni-radtan — omnidirectional with radial-tangential distortion
omni-radtan — omnidirectional with radial-tangential distortion
Extends the Mei omnidirectional model with the Brown-Conrady radial-tangential distortion coefficients. This is the appropriate choice for catadioptric systems where the lens element introduces measurable distortion on top of the mirror geometry.Parameters:
[xi, fx, fy, cx, cy, k1, k2, p1, p2] — 9 totalConstraints: xi >= 0Use when: You have a catadioptric camera with noticeable lens distortion. This is the most complete model for omnidirectional cameras in Kalibr.Command-line model string: omni-radtanRolling shutter variant: omni-radtan-rseucm-none — Extended Unified Camera Model
eucm-none — Extended Unified Camera Model
The Extended Unified Camera Model (EUCM) generalizes the Mei model by adding a second shape parameter
beta. Together, alpha and beta provide a compact two-parameter model that can accurately represent cameras with very wide fields of view, including fisheye lenses, without requiring a separate distortion model.Parameters: [alpha, beta, fx, fy, cx, cy] — 6 totalConstraints: 0 <= alpha < 1, beta >= 0Use when: You want a unified model for wide-angle cameras without adding distortion parameters. EUCM can often match or exceed the accuracy of pinhole-equi with fewer parameters.Command-line model string: eucm-noneds-none — Double Sphere model
ds-none — Double Sphere model
The Double Sphere model represents the camera geometry using two sphere projections parameterized by
xi and alpha. It was introduced to address limitations of the Extended Unified model for very large fields of view. The model has a closed-form inverse, making it efficient to use in optimization.Parameters: [xi, alpha, fx, fy, cx, cy] — 6 totalConstraints: 0 <= alpha < 1Use when: You have a fisheye or catadioptric camera with a very large field of view (approaching or exceeding 180°) and want a compact, analytically invertible model.Command-line model string: ds-noneSee the Double Sphere paper for a detailed comparison of all projection models available in Kalibr.Rolling shutter variants
For rolling shutter cameras, append-rs to the model string and use kalibr_calibrate_rs_cameras instead of kalibr_calibrate_cameras. The rolling shutter calibrator additionally estimates the line delay — the time between the exposure of consecutive rows — which is stored in the output camchain.yaml as line_delay.
| Standard model | Rolling shutter variant |
|---|---|
pinhole-radtan | pinhole-radtan-rs |
pinhole-equi | pinhole-equi-rs |
omni-radtan | omni-radtan-rs |
-rs suffix), so you can also calibrate a global shutter camera with it by omitting the suffix.
Choosing a model for your lens
Use the following guidance when deciding which model to pass to--models:
- Standard lens, FOV < 120°: use
pinhole-radtan. It is robust, fast to optimize, and understood by most downstream tools. - Fisheye or wide-angle lens, FOV > 120°: use
pinhole-equi. The four-coefficient equidistant model handles extreme distortion well. - Single-parameter fisheye: use
pinhole-fovif you want a simpler model and your lens distortion can be captured by one coefficient. - Catadioptric (mirror) system: use
omni-noneoromni-radtan(with distortion if needed). - Very wide-angle or full-hemisphere, prefer compact model: use
eucm-noneords-none.
When the optimizer diverges, check that your model choice matches the actual lens. A
pinhole-radtan model fitted to a fisheye lens will fail to initialize because radial-tangential distortion cannot represent the extreme barrel distortion. Try pinhole-equi or pinhole-fov instead.Output: camchain.yaml camera parameters
After calibration, each camera’s parameters are written tocamchain.yaml. The exact fields depend on the model used.
xi parameter first: