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.

After running kalibr_calibrate_imu_camera, you have a <bagtag>-camchain-imucam.yaml and a <bagtag>-imu.yaml containing the full spatial and temporal calibration of your sensor rig. The Kalibr exporter scripts convert these files into the configuration formats expected by popular VIO (Visual-Inertial Odometry) and SLAM frameworks, saving you from manually transcribing matrix values. All exporters are standalone Python scripts installed alongside Kalibr. Each reads your Kalibr output files and produces one or more framework-specific configuration files.

kalibr_maplab_config

Converts between Kalibr format and the maplab VIO framework format. The script handles both directions: Kalibr → maplab and maplab → Kalibr. Kalibr → maplab sensors.yaml:
kalibr_maplab_config \
  --cam recording-camchain-imucam.yaml \
  --imu recording-imu.yaml \
  --out sensors.yaml
Kalibr → maplab ncamera.yaml (camera-only, no IMU):
kalibr_maplab_config \
  --cam recording-camchain-imucam.yaml \
  --to-ncamera \
  --out ncamera.yaml
maplab → Kalibr:
kalibr_maplab_config \
  --cam sensors.yaml \
  --out recording-camchain-imucam.yaml \
  --imu-out recording-imu.yaml
FlagDescription
--camInput camera YAML (Kalibr camchain-imucam.yaml or maplab sensors.yaml/ncamera.yaml)
--imuInput Kalibr IMU YAML (only for Kalibr → maplab conversion)
--labelNCamera label name (default: ncamera)
--outOutput file path (auto-named if omitted)
--imu-outIMU output file path (maplab → Kalibr only)
--to-ncameraProduce ncamera.yaml instead of full sensors.yaml
The script auto-detects the input format by looking for cam0 (Kalibr format) or ncameras (maplab format) keys at the top level.

kalibr_okvis_config

Converts a camchain-imucam.yaml to the YAML camera block format used by OKVIS, an open keyframe-based visual-inertial odometry system.
kalibr_okvis_config \
  --cam recording-camchain-imucam.yaml \
  --mav MY_MAV_NAME \
  --out okvis_config.yaml
If --out is omitted, the configuration block is printed to stdout so you can copy it manually.
FlagDescription
--camKalibr camchain-imucam.yaml input file
--mavName of the MAV/platform (used for the base_topic path)
--outOutput file path (optional; prints to stdout if omitted)
OKVIS only supports the pinhole projection model. Cameras using omni, eucm, or ds models will be skipped with a warning.
The output is a YAML snippet containing a cameras: block with T_SC (sensor-to-camera transform), image dimensions, distortion coefficients, distortion type, focal length, and principal point for each camera.

kalibr_msf_config

Converts two camchain-imucam.yaml files — one calibrated relative to a VI IMU and one relative to a MAV IMU — into a MSF (Multi-Sensor Fusion) ROS parameter file. MSF is a graph-based sensor fusion framework that fuses IMU, camera, and other sensor data.
kalibr_msf_config \
  --viimu recording-vi-camchain-imucam.yaml \
  --mavimu recording-mav-camchain-imucam.yaml \
  --out msf_config.yaml
If --out is omitted, the configuration block is printed to stdout.
FlagDescription
--viimuKalibr camchain-imucam.yaml calibrated relative to the VI IMU
--mavimuKalibr camchain-imucam.yaml calibrated relative to the MAV IMU
--outOutput file path (optional; prints to stdout if omitted)
The script computes the relative transformation between the two IMUs from T_cam_imu entries, extracts the time delay from timeshift_cam_imu, and inserts these values into an MSF parameter template.

kalibr_rovio_config

Converts a camchain-imucam.yaml to the .info configuration format used by ROVIO, a robust visual-inertial odometry estimator based on iterated extended Kalman filtering.
kalibr_rovio_config \
  --cam recording-camchain-imucam.yaml
The script writes two types of output files in the current directory:
  • rovio_test.info — main ROVIO configuration with IMU-to-camera extrinsics (qCM_x/y/z/w and MrMC_x/y/z) for each camera
  • rovio_cam0.yaml, rovio_cam1.yaml, … — per-camera intrinsic files in ROS camera calibration format
FlagDescription
--camKalibr camchain-imucam.yaml input file
ROVIO only supports the pinhole projection model. Cameras using omni, eucm, or ds models will be skipped with a warning.
ROVIO uses Hamilton quaternion convention. The exporter accounts for the difference between Kalibr’s JPL quaternion convention and Hamilton convention when writing qCM values.

Framework summary

ExporterFrameworkOutput formatBidirectional
kalibr_maplab_configmaplabsensors.yaml / ncamera.yamlYes
kalibr_okvis_configOKVISYAML camera blockNo
kalibr_msf_configMSFROS parameter YAMLNo
kalibr_rovio_configROVIO.info + per-camera YAMLNo

Build docs developers (and LLMs) love