Skip to content

Camera IMU Calibration

Stephanie Tsuei edited this page Jun 10, 2022 · 12 revisions

The below instructions (and any in linked pages) need to be followed carefully!

An accurate camera-IMU calibration is very important for performance of monocular VIO. This page outlines our process for using XIVO with a brand-new sensor. All provided helper scripts assume that data is collected into a rosbag.

External tools we use are:

  1. imu_tk (distributed with XIVO in thirdparty)
  2. Kalibr
  3. Allan Variance ROS

Instructions for Calibration

1. Find a sample time duration tau.

The time duration tau will be used in IMU intrinsic calibration.

  1. Collect several minutes of data where the IMU is not moving.
  2. For both the gyroscope and accelerometer, compute the Allan variance using many interval lengths using our provided script and find the value above which all Allan variances stop changing. For example (using the Intel RealSense d435i)
python scripts/calibration/allan_plot.py --bag [/path/to/bag] --topic /camera/imu

produces the following Allen plots:

Accelerometer Allen Variance vs. Tau Gyroscope Allen Variance vs. Tau

An appropriate value for Tau in both plots is 50 seconds.

2. IMU Intrinsics Calibration

XIVO uses the scale-misalignment model given in Tedaldi et al. and implemented in imu_tk. Follow the instructions in the paper to collect a sequence.

  • The initial static interval period should be roughly tau seconds long.
  • Although only a minimum of 9 short (3-4 second) intervals, each at a different orientation, are required, we recommend collecting 40-50 intervals. This provides more data to imu_tk in case it is not able to perfectly extract 9 perfect intervals.
  • Edit imu_tk's sample application thirdparty/imu_tk/apps/test_imu_calib.cpp with your values of tau, local gravity magnitude, and initial guesses for bias and scale. The sample file test_imu_calib.cpp illustrates a case where raw IMU measurements are not given in typical SI units (e.g. meters, radians). We also provide a sample file thirdparty/imu_tk/apps/phab_calib.cpp that is appropriate for a sensor that outputs measurements in typical SI units.
  • The script scripts/calibration/extract_rosbag_for_imutk.py extracts accelerometer and gyroscope data from a rosbag into the format that imu_tk expects.
  • imu_tk will output two files containing parameters, accel.calib and gyro.calib which will be used in later steps.
  • In XIVO's .cfg file, put the calibration parameters into the imu section. Set parameter imu_tk_convention to true.

3. IMU Noise and Drift Characterization

  1. Collect ~4 hours of IMU data with no motion.
  2. Extract the rosbag into a folder named seq_name
python scripts/calibration/bag_to_frames.py --bag [/path/to/bagfile] --cam_topic [topic name] --imu_topic [topic name] --sequence_name [seq_name]
  1. Correct the IMU measurements of the contents in the folder:
python scripts/correct_imu.py --input [/path/to/seq_name/imu0/data.csv] --output [/path/to/seq_name/imu.csv] --gyro_calib [/path/to/gyro.calib] --accel_calib [/path/to/accel.calib]
  1. Reassemble the corrected IMU measurements and (untouched) RGB images into a correct rosbag.
rosrun kalibr kalibr_bagcreater --folder /path/to/seq_name --output-bag corrected_bagfile.bag

The topic names in this corrected rosbag will be /cam0/image_raw and /imu.

  1. Use Allan Variance ROS to compute noise and drift parameters. (In the input .yaml file, put the approximate IMU sample rate (in Hz) for both the measure_rate and imu_rate fields.)

  2. Create an input IMU .yaml file for Kalibr as described here. Note the warning on the bottom of this page that noise parameters will have to be inflated.

4. Camera Intrinsics Calibration

Use Kalibr's camera calibration tool.

5. Camera-IMU Extrinsics and Time-Delay Calibration

  1. Collect a sufficiently exciting 6-DOF motion sequence in front of a calibration target (an aprilgrid or checkboard).
  2. Correct the IMU values in the collected rosbag using intrinsics from imu_tk and reassemble. This is the same as steps 2-4 in part 3.
  3. Calibrate using Kalibr's Camera-IMU Calibration Tool. Since we have already corrected the IMU measurements using the output from imu_tk, the correct imu intrinsic model (--imu-models) is calibrated.

General Tips

How do you know your calibration is good?

What is "sufficiently exciting"?