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_imu_camera determines the rigid-body transformation between each camera in a chain and an IMU (T_cam_imu), the temporal offset between camera and IMU timestamps, and optionally additional IMU intrinsic parameters such as axis misalignment and scale factors. The optimizer fits a continuous-time B-spline trajectory to the combined sensor data, which makes it robust to imperfect synchronization and different sampling rates.
Camera-IMU calibration requires a pre-calibrated camera chain. Run multi-camera calibration first and use the resulting
camchain.yaml as input here.Prerequisites
- A ROS bag with image topics (from every camera in the chain) and at least one IMU topic, recorded together while moving the rig in front of an AprilGrid target
camchain.yaml— output ofkalibr_calibrate_camerasimu.yaml— IMU noise parameter file (see IMU YAML reference)aprilgrid.yaml— target configuration (same file used for camera calibration)
IMU YAML format
The IMU YAML file describes the noise characteristics of the IMU and the ROS topic on which measurements are published. Noise parameters are typically taken from the IMU datasheet and should be in the continuous-time (rate-density) form.imu.yaml (ADIS16448 example)
IMU models
The--imu-models flag selects the complexity of the IMU intrinsic model to estimate:
| Model | Parameters estimated | Use when |
|---|---|---|
calibrated | None (uses provided noise values only) | Factory-calibrated IMUs, single-IMU setups |
scale-misalignment | Scale matrix and axis misalignment for both gyroscope and accelerometer | When axis alignment errors are significant |
scale-misalignment-size-effect | All of the above plus accelerometer lever-arm offsets | High-quality IMUs where size-effect matters |
--imu-models is omitted, the tool defaults to calibrated for backward compatibility.
Step-by-step calibration
Record a calibration bag
Move the camera-IMU rig in front of the AprilGrid target with deliberate, varied motion:
- Include all six degrees of freedom — translations along each axis and rotations about each axis
- Excite each axis independently as well as in combination
- Maintain the target in the camera field of view throughout
- Record for at least 30–60 seconds of continuous motion
Prepare configuration files
Ensure you have three YAML files ready:The
camchain.yaml must include the rostopic field for each camera — Kalibr reads image data directly from the bag using those topic names.Run the calibrator
Review the output files
Output files are written using the bag filename as a prefix:
Check the PDF report for:
| File | Contents |
|---|---|
MYROSBAG-camchain-imucam.yaml | Extended camera chain including T_cam_imu and time offsets for each camera |
MYROSBAG-imu.yaml | Calibrated IMU parameters (pose relative to body frame, time offset, and intrinsics if estimated) |
MYROSBAG-results-imucam.txt | Full numeric results including residual statistics |
MYROSBAG-report-imucam.pdf | Visual report with reprojection errors, IMU residuals, and trajectory plots |
- Reprojection errors centered near zero
- IMU accelerometer and gyroscope residuals without strong temporal structure (structure indicates unmodeled dynamics or poor excitation)
- A time offset that is plausible for your hardware setup (typically under 50 ms for software-synchronized systems)
Using a non-default IMU model
To use thescale-misalignment model instead of the default calibrated:
--imu-models flag must be given once for each --imu file.
IMU rate and camera rate considerations
The optimizer works best when the IMU sampling rate is significantly higher than the camera frame rate. A ratio of 10:1 or higher (for example, 200 Hz IMU with 20 Hz cameras) is typical and recommended. At lower ratios, the continuous-time spline has less IMU data to anchor it between camera frames, which degrades the spatial and temporal estimates.The
update_rate field in imu.yaml must match the actual publishing rate of the IMU topic in the bag. An incorrect value scales the noise covariance incorrectly and degrades calibration quality.Recovering parameter covariance
To recover the covariance of the calibration design variables (useful for understanding parameter uncertainty):Additional options
| Flag | Default | Description |
|---|---|---|
--bag-from-to T0 T1 | full bag | Process only the bag segment from T0 to T1 seconds |
--bag-freq F | all frames | Subsample images at F Hz |
--max-iter N | 30 | Maximum optimizer iterations |
--timeoffset-padding S | 0.03 | Time window (seconds) in which the time offset may vary during optimization |
--export-poses | off | Export optimized trajectory to CSV |
Multi-camera calibration
Run this step first to produce the camchain.yaml input required here.
IMU noise model
Background on IMU noise parameters and how to determine them from datasheets or Allan variance analysis.