Skip to content

Calibration

XuRobotics edited this page Jul 25, 2021 · 11 revisions

Use equidistant distortion model! radtan does not work properly with multicam

Calibration uses multicam_calibration and kalibr.

Before executing these steps, you should collect 2 rosbags with stereo camera and imu data. The first bag is for camera-camera calibration and consists of a static robot and moving calibration board. The second bag is for camera-imu calibration and consists of a static calibration board and moving robot. To see the motions, you can watch this video.

We recommend using rosbags because kalibr requires rosbags. multicam_calibration can use both a live stream or with a rosbag, but we also recommend using a rosbag.

Overview

Calibration consists of three steps:

  1. Calibrate the stereo cameras to each other using either multicam_calibration or kalibr
  2. Calibrate the cameras with IMU using kalibr
  3. Convert the output kalibr yaml into the proper yaml format required by S-MSCKF

You may want to recalibrate the stereo cameras, but not the stereo-imu:

  1. Calibrate the stereo cameras to each other using multicam_calibration
  2. Update the current kalibr yaml using the output multicam_calibration yaml

Docker

All of the necessary packages and dependencies are located in a docker image

kumarrobotics/autonomy:calibration

You can either download this docker image:

docker pull kumarrobotics/autonomy:calibration

Or you can build it. Assuming the autonomy_stack repo is located in $HOME/autonomy_stack:

cd $HOME/autonomy_stack/calibration/docker
./build.sh

Run the docker image using the runGUI.sh script in the calibration folder. This script will launch a docker container with GUI support (may need to modify if your computer has no GPU). In addition, it will mount as a volume to the container:

  1. ${PWD}/calib_files: contains the calibration files
  2. ${HOME}/bags: contains the 2 rosbags for both the stereo-cam calibration, and the cam-imu calibration

Assuming the autonomy_stack repo is located in $HOME/autonomy_stack: cd $HOME/autonomy_stack/calibration/docker ./runGUI.sh

You will now be inside the docker container, which is where you will run all the following commands.

Camera-Camera calibration

There are two methods. If you have an initial guess of the camera parameters, you should use multicam_calibration. If you do not have an initial guess of the camera parameters, you should use Kalibr.

Multicam Calibration

The below commands mirror the instructions located in multicam_calibration, with slight modifications to automatically map the correct directories.

Note:

(1) multicam_calibration is using opencv3, if there are any packages that are using another version of opencv, there might be a conflict, please force their usage of opencv3 if possible.

(2) put individual pkgs in the apriltag repo into the src folder of the workspace before building.

Launch the calibration.launch file:

roslaunch calibration_launch calibration.launch

In a separate terminal, play the calibration bag:

rosbag play calibration.bag

When you have enough frames collected, start the calibration:

rosservice call /multicam_calibration/calibration

The calibration output will autonmatically be saved in the calib_files/multicam directory (on the native system).

Note that multicam_calibration requires an initial guess of the camera calibration. If this initial guess is not available, you can instead use Kalibr.

Kalibr camera-camera

The following steps make these assumptions:

  1. calibration bag is located at ~/bags/calibration.bag (inside the docker container). This should be mapped correctly using the runGUI.sh script if you placed your rosbag in $HOME/bags directory in your host system
  2. camera topics are /emu1/sync/cam0/image_raw and /emu1/sync/cam1/image_raw
  3. aprilgrid.yaml is located at ~/calib_files/aprilgrid.yaml (inside the docker container). This should be mapped correctly using the runGUI.sh script

While inside the docker container, move into the calib_files directory (located at ~/calib_files), as Kalibr will save the output files into the current directory. If you are not in the calib_files directory, you will have to manually move the output files into this directory, otherwise they will disappear once you exit the docker container:

cd ~/calib_files

Calibrate the cameras, specifying the correct calibration bag, camera topics, and april tag configuration. This step will take a while (~10-15 minutes):

kalibr_calibrate_cameras --bag ~/bags/calibration.bag --topics /emu1/sync/cam0/image_raw /emu1/sync/cam1/image_raw --models pinhole-equi pinhole-equi --target ~/calib_files/aprilgrid.yaml

Camera-IMU calibration

You will use Kalibr to perform the camera-imu calibration.

The following steps make these assumptions:

  1. calibration bag is located at ~/bags/calibration.bag (inside the docker container). This should be mapped correctly using the runGUI.sh script if you placed your rosbag in ${HOME}/bags in your host system.
  2. output yaml from Camera-Camera calibration (either multicam_calibration or kalibr) is located at ~/calib_files/multicam/emu1-latest.yaml
  3. imu parameters are located in `~/calib_files/kalibr/emu1-imu.yaml'

emu1-imu.yaml:

#Accelerometers
accelerometer_noise_density: 1.0e-03   #Noise density (continuous-time)
accelerometer_random_walk:   1.0e-04   #Bias random walk

#Gyroscopes
gyroscope_noise_density:     1.0e-04   #Noise density (continuous-time)
gyroscope_random_walk:       1.0e-05   #Bias random walk

rostopic:                    /emu1/sync/imu/imu      #the IMU ROS topic
update_rate:                 200.0     #Hz (for discretization of the values above)
  1. aprilgrid.yaml is located at ~/calib_files/aprilgrid.yaml. This should be mapped correctly using the runGUI.sh script.

If you're using apriltags in the KumarLab, you can use the following aprilgrid.yaml

target_type: 'aprilgrid' #gridtype
tagCols: 7               #number of apriltags
tagRows: 5               #number of apriltags
tagSize: 0.04            #size of apriltag, edge to edge [m]
tagSpacing: 0.25         #ratio of space between tags to tagSize
                         #example: tagSize=2m, spacing=0.5m --> tagSpacing=0.25[-]

While inside the docker container, move into the calib_files directory:

cd ~/calib_files

Calibrate the cameras and IMU, specifying the correct calibration bag, camera topics, and april tag configuration:

kalibr_calibrate_imu_camera --bag ~/bags/calibration.bag --cam ~/calib_files/multicam/emu1-latest.yaml --imu ~/calib_files/kalibr/emu1-imu.yaml --target ~/calib_files/aprilgrid.yaml

Convert kalibr yaml format

Move into the calib_files directory insider docker:

cd ~/calib_files

Run the convert_kalibr script. We assume kalibr.yaml is the kalibr output yaml, and output.yaml is where you want to save the converted yaml format.

./convert_kalibr -k kalibr.yaml -o output.yaml

Update kalibr yaml with new multicam calibration

You typically will have to update the camera-camera calibration more frequently than the camera-imu calibration using multicam-calibration.

Using the output file from the multicam_calibration step, you will thenneed to update the kalibr file to be used by S-MSCKF.

Move into the calib_files directory insider docker:

cd ~/calib_files

Run the update_kalibr script. We assume kalibr.yaml is the original kalibr output yaml, and multicam.yaml is recent multicam calibration yaml, and output.yaml is where you want to save the updated yaml format.

./update_kalibr -k kalibr.yaml -m multicam.yaml -o output.yaml

Clone this wiki locally