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.

This guide walks you through a complete first calibration using Kalibr. You will generate an AprilGrid calibration target, record a ROS bag with your camera, run kalibr_calibrate_cameras, and interpret the output. All commands assume you are working inside the Docker container or a sourced ROS workspace — see the installation guide if you have not set that up yet.
If you are using Docker, start the container and source the workspace before running any Kalibr commands:
source /catkin_ws/devel/setup.bash

Before you begin

You need:
  • Kalibr installed (Docker or source build)
  • A camera publishing images on a ROS topic
  • A printer capable of printing at the correct physical scale

1

Generate a calibration target PDF

Kalibr provides kalibr_create_target_pdf to generate print-ready calibration targets. The AprilGrid is the recommended target type — it is robust to partial occlusions because each tag has a unique ID.
kalibr_create_target_pdf \
  --type apriltag \
  --nx 6 \
  --ny 6 \
  --tsize 0.08 \
  --tspace 0.3
FlagMeaning
--type apriltagAprilTag-based grid target
--nx 6Number of tags along the x axis
--ny 6Number of tags along the y axis
--tsize 0.08Physical tag size in metres (here 8 cm)
--tspace 0.3Tag spacing as a fraction of tag size (30%)
This produces a PDF file (target.pdf) in the current directory.
Print the PDF at exactly 100% scale — do not scale to fit the page. Measure a tag after printing to confirm it matches the --tsize value. Any discrepancy will directly degrade calibration accuracy.
The calibration target configuration used in subsequent steps must match what you passed to kalibr_create_target_pdf. Save an aprilgrid.yaml file:
target_type: 'aprilgrid'
tagCols: 6
tagRows: 6
tagSize: 0.088   # metres — set this to your actual printed tag size
tagSpacing: 0.3  # fraction of tagSize
Measure the printed tag size with a ruler and update tagSize in the YAML to match. Even a few millimetres of error matters.
2

Record a ROS bag with camera data

Mount the printed target rigidly (on a flat wall or clipboard) and move the camera in front of it — or hold the target and move it in front of a static camera. You need to cover the full field of view with many different viewing angles.Record camera images to a ROS bag:
rosbag record -O calibration.bag /cam0/image_raw
Replace /cam0/image_raw with the actual topic name your camera publishes on.Tips for a good calibration bag:
  • Record at least 60–80 frames where the full target is visible.
  • Tilt and rotate the camera (or target) significantly — pure planar motion does not constrain all intrinsics.
  • Include close and far distances to the target.
  • Keep movements slow and steady to avoid motion blur.
  • Aim for good, consistent lighting with no glare on the target.
For a multi-camera rig, record all camera topics simultaneously:
rosbag record -O calibration.bag /cam0/image_raw /cam1/image_raw
3

Run camera calibration

Run kalibr_calibrate_cameras with your bag file, target configuration, camera model, and image topic:
kalibr_calibrate_cameras \
  --models pinhole-radtan \
  --target aprilgrid.yaml \
  --bag calibration.bag \
  --topics /cam0/image_raw
For a two-camera rig, specify one model and one topic per camera:
kalibr_calibrate_cameras \
  --models pinhole-radtan pinhole-radtan \
  --target aprilgrid.yaml \
  --bag calibration.bag \
  --topics /cam0/image_raw /cam1/image_raw
Choosing a camera model:
Model stringWhen to use
pinhole-radtanStandard lens, moderate field of view
pinhole-equiWide-angle or fisheye lens
pinhole-fovFisheye lens with field-of-view model
omni-radtanOmnidirectional camera
ds-noneDouble Sphere model (fisheye)
Kalibr selects which images to include based on a mutual-information criterion. It is normal for many frames to be skipped — the tool prints progress and reports how many views were used.
4

Review the output files

When calibration completes, Kalibr writes three output files named after your bag file (for example, calibration-camchain.yaml, calibration-results-cam.txt, and calibration-report-cam.pdf).calibration-camchain.yaml — the primary result file. It contains the intrinsic parameters for each camera and, for multi-camera rigs, the extrinsic transforms between cameras:
cam0:
  camera_model: pinhole
  intrinsics: [461.629, 460.152, 362.680, 246.049]  # fx fy cx cy
  distortion_model: radtan
  distortion_coeffs: [-0.27695497, 0.06712482, 0.00087538, 0.00011556]
  resolution: [752, 480]
  rostopic: /cam0/image_raw
calibration-results-cam.txt — a detailed text report with reprojection error statistics and optimizer output.calibration-report-cam.pdf — a visual report with reprojection error plots, detected corners, and camera geometry diagrams.
Check the reprojection error in the PDF report. A mean reprojection error below 0.5 pixels indicates a good calibration. Errors above 1 pixel suggest problems with the target size, camera model choice, or image quality.

What to do next

Camera-IMU calibration

Use the camchain.yaml output from this step as input to calibrate an IMU against your camera system.

Multi-camera calibration guide

Learn advanced options for calibrating rigs with more than two cameras or non-overlapping fields of view.

AprilGrid target reference

Full reference for AprilGrid configuration options and printing guidance.

Camera models

Understand the projection and distortion model options available in Kalibr.

Build docs developers (and LLMs) love