Kalibr Camera IMU Calibration - ripl-lab/allan_variance_ros2 GitHub Wiki

RealSense Camera IMU System Calibration with Kalibr

OpenVINS implements online estimation of the extrinsic and time offset parameters between the camera and the IMU. Problems:

  • IMU requires estimating of additional vias terms
  • Requires highly accurate calibration between the IMU and camera
  • Small error sin relative timestamps between the sensors can degrade the performance in dynamic trajectories

Kalibr is a tool for calibrating the extrinsic and time offset parameters between the camera and the IMU.

Repo for Kalibr: https://github.com/ethz-asl/kalibr

The following guide is based on the original guide for calibration with some modifications to work with the RealSense camera and IMU, as well as some missing steps: https://docs.openvins.com/gs-calibration.html

Step 1: IMU Calibration

Follow the instructions for IMU calibration using the allan_variance_ros2 repo: https://github.com/ripl-lab/allan_variance_ros2 using the instructions in the wiki.

These instructions will generate an imu.yaml file containing the IMU parameters needed for the Kalibr calibration. The specific parameters needed are:

Parameter YAML element Symbol Units
Gyroscope "white noise" gyroscope_noise_density σg rad/s √Hz-1
Accelerometer "white noise" accelerometer_noise_density σa m/s² √Hz-1
Gyroscope "random walk" gyroscope_random_walk σbg rad/s² √Hz-1
Accelerometer "random walk" accelerometer_random_walk σba m/s³ √Hz-1

Step 2: Camera Intrinsic Calibration

Calibrate the camera intrinsic values such as the focal length, camera center, and distortion coefficients (Original reference: https://github.com/ethz-asl/kalibr/wiki/installation)

  1. Clone and build https://github.com/ethz-asl/kalibr/
git clone https://github.com/ethz-asl/kalibr.git
cd kalibr
docker build -t kalibr -f Dockerfile_ros1_20_04 .
  1. Get a calibration board printed and a corresponding YAML file describing it as below
target_type: 'aprilgrid' #gridtype
tagCols: 6               #number of apriltags
tagRows: 6               #number of apriltags
tagSize: 0.088           #size of apriltag, edge to edge [m]
tagSpacing: 0.3          #ratio of space between tags to tagSize
codeOffset: 0            #code offset for the first tag in the aprilboard
  1. Record a ROS bag of the camera data and ensure that the calibration board can be seen from different orientations, distances, and in each part of the image plane. You can either move the calibration board and keep the camera still or move the camera and keep the calibration board stationary.
    • This can either be recorded in ROS1 to a .bag file or ROS2 to an .mcap file and then converted to a .bag file which is what is described below.
    • The topics to record from the Intel RealSense D435i camera are:
      • /camera/camera/color/image_raw
      • /camera/camera/infra1/image_rect_raw - Left camera
      • /camera/camera/infra2/image_rect_raw - Right camera
    • The following steps are assuming the realsense ROS2 wrapper is already installed or using the devcontainer of the allan_variance_ros2 repo as described in the Using Realsense with ROS2 documentation.
# Source your workspace
source ~/ros2_ws/install/local_setup.bash

# Launch the RealSense node
# Unite IMU method needs to be set to `2` so accel and gyro are on the same /camera/camera/imu topic
# Here, the infra cameras are recorded at Record at 848x480 at 30 FPS (also has 1280x720, 640x480 etc..) and the rgb camera at 1280x720 at 30 FPS
ros2 launch realsense2_camera rs_launch.py enable_accel:=true enable_gyro:=true unite_imu_method:=2 enable_infra1:=true enable_infra2:=true depth_module.infra_profile:=848x480x30 rgb_camera.color_profile:=1280x720x30

# To view camera streams from published topics, can either use rqt_image_view and select the topic in the dropdown, or add an Image panel in rviz
ros2 run rqt_image_view rqt_image_view
ros2 run rviz2 rviz2

# In a new terminal, record the data while moving the camera around to see the calibration board from different orientations, distances, and in each part of the image plane for about 30 seconds.
ros2 bag record /camera/camera/infra1/image_rect_raw /camera/camera/infra2/image_rect_raw -s mcap

# Convert the mcap file to a bag file
rosbags-convert --src <ros2_bag_folder> --dst realsense_camera_calibration.bag
  1. Run the camera intrinsic calibration
# Set the folder where the rosbag of the camera data recorded in step 3 is located, as well as the YAML file describing the calibration board.
FOLDER=/path/to/your/data/on/host

xhost +local:root

# Run the container
docker run -it -e "DISPLAY" -e "QT_X11_NO_MITSHM=1" -v "/tmp/.X11-unix:/tmp/.X11-unix:rw" -v "$FOLDER:/data" kalibr

# Source the workspace
source devel/setup.bash

# Run the calibration
# Here, need to specify models parameter, one for each camera, either pinhole-equi or pinhole-radtan
rosrun kalibr kalibr_calibrate_cameras --bag /data/realsense_camera_calibration.bag --target /data/april_6x6.yaml --models pinhole-radtan pinhole-radtan --topics /camera/camera/infra1/image_rect_raw /camera/camera/infra2/image_rect_raw --bag-freq 10.0 --show-extraction
  1. Inspect final results in the PDF file that is generated. pay close attention to the final reprojection error graphs, with a good calibration having less than < 0.2-0.5 pixel reprojection errors.
  • Camera Intrinsic Calibration Result

Step 3: Camera-IMU Calibration

The camera-imu calibration tool estimates the spatial and temporal parameters of a camera system with respect to an intrinsically calibrated IMU. (Original reference: https://github.com/ethz-asl/kalibr/wiki/camera-imu-calibration)

  1. (Same as step 1 above) Clone and build https://github.com/ethz-asl/kalibr/
git clone https://github.com/ethz-asl/kalibr.git
cd kalibr
docker build -t kalibr -f Dockerfile_ros1_20_04 .
  1. (Same as step 2 above) Get a calibration board printed and a corresponding YAML file describing it as below
target_type: 'aprilgrid' #gridtype
tagCols: 6               #number of apriltags
tagRows: 6               #number of apriltags
tagSize: 0.088           #size of apriltag, edge to edge [m]
tagSpacing: 0.3          #ratio of space between tags to tagSize
codeOffset: 0            #code offset for the first tag in the aprilboard
  1. Record a ROS bag and ensure that the calibration board can be seen from different orientations, distances, and mostly in the center of the image. You should move in smooth non-jerky motions with a trajectory that excites as many orientation and translational directions as possible at the same time. A 30-60 second dataset is normally enough to allow for calibration.
    • This can either be recorded in ROS1 to a .bag file or ROS2 to an .mcap file and then converted to a .bag file which is what is described below.
      • The topics to record from the Intel RealSense D435i camera are:
        • /camera/camera/imu at 200 Hz
        • /camera/camera/infra1/image_rect_raw - Left camera
        • /camera/camera/infra2/image_rect_raw - Right camera
        • /camera/camera/color/image_raw at 20 Hz, Do not need this if using the stereo cameras
      • The following steps are assuming the realsense ROS2 wrapper is already installed or using the devcontainer of the allan_variance_ros2 repo as described in the Using Realsense with ROS2 documentation.
# Source your workspace
source ~/ros2_ws/install/local_setup.bash

# Launch the RealSense node
ros2 launch realsense2_camera rs_launch.py enable_accel:=true enable_gyro:=true unite_imu_method:=2 enable_infra1:=true enable_infra2:=true depth_module.infra_profile:=848x480x30 rgb_camera.color_profile:=1280x720x30

# To view camera streams from published topics, can either use rqt_image_view and select the topic in the dropdown, or add an Image panel in rviz
ros2 run rqt_image_view rqt_image_view
ros2 run rviz2 rviz2

# In a new terminal, record the data while moving the camera around to see the calibration board from different orientations, distances, and in each part of the image plane for about 30 seconds.
ros2 bag record /camera/camera/infra1/image_rect_raw /camera/camera/infra2/image_rect_raw /camera/camera/imu -s mcap

# Convert the mcap file to a bag file
rosbags-convert --src <ros2_bag_folder> --dst realsense_camera_imu_calibration.bag
  1. Run the camera-imu calibration
    • First in the imu.yaml generated in step 1, ensure the imu topic is correct, and you may need to scale the parameters by 5x the white noise values and 10x the random walk values as suggested in the Kalibr documentation to account for unmodelled effects. Attempt first without scaling and see how accurate the result plots are within the 3-sigma error bounds.
    • Then run the following command to perform the calibration
# Set the folder on your local where the following files are placed:
# rosbag of the camera-imu data recorded in step 3 right before this step
# camchain.yaml file generated in Step 2: Camera Intrinsic Calibration
# imu.yaml file generated in Step 1: IMU Calibration
# YAML file describing the calibration board.
FOLDER=/path/to/your/data/on/host

xhost +local:root

# Run the container
docker run -it -e "DISPLAY" -e "QT_X11_NO_MITSHM=1" -v "/tmp/.X11-unix:/tmp/.X11-unix:rw" -v "$FOLDER:/data" kalibr

# Source the workspace
source devel/setup.bash

# Run the calibration
# Here, need to specify IMU Models, either scale-misalignment or calibrated (default)
# the --cam config is the yaml generated in the camera calibration in Step 2: Camera Intrinsic Calibration above
rosrun kalibr kalibr_calibrate_imu_camera --bag [realsense_camera_imu_calibration.bag] --cam [camchain.yaml] --imu [imu.yaml] --imu-models calibrated --target [target.yaml] --reprojection-sigma 1.0 --show-extraction
  1. Inspect the final result. You will want to make sure that the spline fitted to the inertial reading was properly fitted. Your accelerometer and gyroscope errors are within their 3-sigma bounds (if not then your IMU noise or the dataset are incorrect). Ensure that your estimated biases do not leave your 3-sigma bounds. If they do leave then your trajectory was too dynamic, or your noise values are not good. Sanity check your final rotation and translation with hand-measured values.
    • Camera-IMU Calibration Result
⚠️ **GitHub.com Fallback** ⚠️