Skip to main content

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.

kalibr_calibrate_cameras estimates the intrinsic parameters and the extrinsic baselines between two or more cameras. It reads synchronized image topics from a ROS bag, detects a calibration target in every frame, and runs a batch optimization to produce a camchain.yaml file, a detailed results text file, and a PDF report.

Synopsis

kalibr_calibrate_cameras --models <model> [<model> ...] \
                          --topics <topic> [<topic> ...] \
                          --bag <file.bag> \
                          --target <target.yaml>

Example

kalibr_calibrate_cameras \
  --models omni-radtan pinhole-equi \
  --target aprilgrid.yaml \
  --bag MYROSBAG.bag \
  --topics /cam0/image_raw /cam1/image_raw
aprilgrid.yaml:
target_type: 'aprilgrid'
tagCols: 6
tagRows: 6
tagSize: 0.088  # meters
tagSpacing: 0.3 # fraction of tagSize

Camera models

Pass one --models value per topic, in the same order as --topics.
Model stringProjectionDistortion
pinhole-radtanPinholeRadial-tangential
pinhole-equiPinholeEquidistant (fisheye)
pinhole-fovPinholeField-of-view
omni-noneOmnidirectionalNone
omni-radtanOmnidirectionalRadial-tangential
eucm-noneExtended UnifiedNone
ds-noneDouble SphereNone

Flags

Camera models

--models
string[]
required
One or more camera model strings, one per topic. Accepted values: pinhole-radtan, pinhole-equi, pinhole-fov, omni-none, omni-radtan, eucm-none, ds-none. The number of models must match the number of --topics values.

Data source

--bag
string
Path to the ROS bag file containing image data.
--topics
string[]
required
One or more ROS image topic names, one per camera. The order must match --models.
--bag-from-to
float float
Use only the bag data within this time window, specified as two values: start and end time in seconds from the start of the bag.
--bag-freq
float
Downsample the bag to this feature extraction frequency in Hz. Useful for large bags to reduce processing time.

Calibration target configuration

--target
string
required
Path to the calibration target configuration YAML file. See target YAML format for the expected structure.

Image synchronization

--approx-sync
float
Time tolerance in seconds for approximate image synchronization across cameras. Default: 0.02.

Calibrator settings

--qr-tol
float
Tolerance on the factors of the QR decomposition used inside the linear solver. Default: 0.02.
--mi-tol
float
Mutual-information threshold for admitting a new image into the estimator. Higher values admit fewer images. Pass -1 to force all images through. Default: 0.2.
--no-shuffle
boolean
Disable random shuffling of the dataset processing order. By default, views are shuffled before optimization to reduce initialization bias.

Outlier filtering options

--no-outliers-removal
boolean
Disable automatic corner outlier filtering during calibration.
--no-final-filtering
boolean
Disable the additional outlier filtering pass run after all views have been processed.
--min-views-outlier
integer
Minimum number of raw views required before outlier statistics are initialized. Default: 20.
--use-blakezisserman
boolean
Enable the Blake-Zisserman M-estimator for robust fitting against large outlier reprojection errors.
--plot-outliers
boolean
Display detected outlier corners visually during extraction. This can be slow on large datasets.

Output options

--verbose
boolean
Enable detailed debug-level logging. Enabling this flag also disables interactive plots.
--show-extraction
boolean
Display each image during calibration target extraction. Enabling this flag disables interactive plots.
--plot
boolean
Plot reprojection errors after each view is added during calibration. This can be slow.
--dont-show-report
boolean
Do not open the PDF report on screen after calibration finishes.
--export-poses
boolean
Export the optimized camera poses to a CSV file with columns: time_ns, position, quaternion.

Output files

After a successful run, three files are written next to the bag file:
FileDescription
<bag>-camchain.yamlCamera chain calibration in camchain YAML format
<bag>-results-cam.txtDetailed numeric results for all cameras
<bag>-report-cam.pdfPDF calibration report with reprojection error plots
<bag>-poses-cam0.csvOptimized poses (only with --export-poses)
If optimization diverges, Kalibr automatically re-initializes intrinsics and retries up to three times. Use --verbose to inspect the extraction quality if it keeps failing.

Build docs developers (and LLMs) love