Skip to content

Calibration

Fernando Cladera edited this page Feb 16, 2022 · 11 revisions

Calibration requires multicam_calibration and kalibr. Please refer to these repos to get the required tools for calibration.

Before executing these steps, you should collect 2 bags 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

The initial calibration process (when you assemble your quad) 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 kalib.
  3. Convert the output kalibr yaml into the proper yaml format required by S-MSCKF

Before each flight, we recommend to perform a stereo camera calibration, but not an IMU calibration:

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

Stereo Camera Calibration

There are two methods for stereo camera calibration:

  • 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.

Initial guess for OVC3b

cam0: rectification_matrix: - [ 0.99998513429, -0.00072231833, 0.00540457690] - [ 0.00071000439, 0.99999714874, 0.00228000146] - [-0.00540620838, -0.00227613029, 0.99998279592] projection_matrix: - [1016.28949887392, 0.00000000000, 652.56153679049, 0.00000000000] - [ 0.00000000000, 1016.28949887392, 329.65089242489, 0.00000000000] - [ 0.00000000000, 0.00000000000, 1.00000000000, 0.00000000000] camera_model: pinhole intrinsics: [1067.96, 1068.1, 641.371, 343.293] distortion_model: equidistant distortion_coeffs: [-0.0964802, 0.00443556, 0.00765515, -0.0180741] resolution: [1280, 800] rostopic: /ovc/left/image_raw cam1: T_cn_cnm1: - [ 0.99999976816, 0.00010526340, -0.00067275668, -0.11983986808] - [-0.00010219715, 0.99998961548, 0.00455614903, 0.00009585961] - [ 0.00067322929, -0.00455607922, 0.99998939440, -0.00072876351] - [ 0.00000000000, 0.00000000000, 0.00000000000, 1.00000000000] rectification_matrix: - [ 0.99998119046, -0.00079988241, 0.00608102979] - [ 0.00081373344, 0.99999707971, -0.00227561086] - [-0.00607919181, 0.00228051640, 0.99997892111] projection_matrix: - [1016.28949887392, 0.00000000000, 652.56153679049, -121.79429175304] - [ 0.00000000000, 1016.28949887392, 329.65089242489, 0.00000000000] - [ 0.00000000000, 0.00000000000, 1.00000000000, 0.00000000000] camera_model: pinhole intrinsics: [1064.59, 1064.79, 664.657, 350.615] distortion_model: equidistant distortion_coeffs: [-0.0963886, -0.00104029, 0.0133809, -0.017335] resolution: [1280, 800] rostopic: /ovc/right/image_raw 

Multicam Calibration

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

  1. Launch the calibration.launch file: roslaunch calibration_launch calibration.launch

  2. In a separate terminal, play the calibration bag: rosbag play calibration.bag

  3. When you have enough frames collected, start the calibration:= rosservice call /multicam_calibration/calibration

The calibration output will automatically be saved in the calib_files/multicam directory.

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 Calibration

The following steps make these assumptions:

  • calibration bag is located at ~/bags/calibration.bag.
  • camera topics are /ovc/left/image_raw and /ovc/right/image_raw
  • aprilgrid.yaml is located at ~/calib_files/aprilgrid.yaml.

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 /ovc/left/image_raw /ovc/right/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.
  2. The output yaml from Camera-Camera calibration (either multicam_calibration or kalibr) is located at ~/calib_files/cam-cam.yaml
  3. Imu parameters are located in `~/calib_files/emu1-imu.yaml'

emu1-imu.yaml for the Vectornav VN100-T:

#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.

At KumarLab we 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[-] 

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/cam-cam.yaml --imu ~/calib_files/emu1-latest.yaml --target 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 then need 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