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_rs_cameras estimates the intrinsic parameters of a single rolling shutter camera, including the per-row time offset introduced by the rolling shutter mechanism. It reads a single image topic from a ROS bag, detects an AprilGrid target, and runs a continuous-time optimization. Global-shutter models are also supported for comparison or fallback.

Synopsis

kalibr_calibrate_rs_cameras --model <model> \
                             --frame-rate <fps> \
                             --topic <topic> \
                             --bag <file.bag> \
                             --target <target.yaml> \
                             --inverse-feature-variance <value>

Example

kalibr_calibrate_rs_cameras \
  --model pinhole-radtan-rs \
  --target aprilgrid.yaml \
  --bag MYROSBAG.bag \
  --topic /cam0/image_raw \
  --inverse-feature-variance 1 \
  --frame-rate 20
aprilgrid.yaml:
target_type: 'aprilgrid'
tagCols: 6
tagRows: 6
tagSize: 0.088  # meters
tagSpacing: 0.3 # fraction of tagSize

Camera models

Model stringProjectionDistortionShutter
pinhole-radtan-rsPinholeRadial-tangentialRolling
pinhole-equi-rsPinholeEquidistant (fisheye)Rolling
omni-radtan-rsOmnidirectionalRadial-tangentialRolling
pinhole-radtanPinholeRadial-tangentialGlobal
pinhole-equiPinholeEquidistant (fisheye)Global
omni-radtanOmnidirectionalRadial-tangentialGlobal
The -rs suffix identifies rolling shutter models. Use global-shutter models (pinhole-radtan, pinhole-equi, omni-radtan) when you want to calibrate a global-shutter camera with this tool.

Flags

--model
string
required
Camera model string. See the table above for accepted values.
--frame-rate
integer
required
Approximate frame rate of the camera in Hz. Used to initialize the rolling shutter time offset.

Data source

--bag
string
Path to the ROS bag file containing image data.
--topic
string
required
ROS image topic name to read from the bag.
--bag-from-to
float float
Use only bag data within this time window: start and end in seconds from the beginning of the bag.
--bag-freq
float
Downsample to this feature extraction frequency in Hz.

Calibration target configuration

--target
string
required
Path to the calibration target configuration YAML file. See target YAML format.
--inverse-feature-variance
float
required
Estimated inverse variance of the feature detector. This value weights the feature observation terms in the optimization. A value of 1 is a common starting point.

Optimization options

--max-iter
integer
Maximum number of optimization iterations. Default: 30.

Output options

--verbose
boolean
Enable detailed debug-level logging. Also disables interactive plots.
--show-extraction
boolean
Display each image during calibration target extraction. Disables interactive plots.
Because rolling shutter calibration models image-plane distortion jointly with the per-row time offset, significant lens distortion can cause the initial transformation estimation to fail. The tool skips transformation estimation internally (noTransformation=True) for this reason — ensure the AprilGrid is clearly and fully visible across the recording.

Build docs developers (and LLMs) love