Link Search Menu Expand Document

Calibrate Cameras

Table of contents

  1. Overview
  2. Recommended Chessboard
  3. Command Line Options
    1. VOXL and VOXL Flight
    2. VOXL 2 and RB5 Flight
  4. Monocular Calibration Process
  5. Stereo Calibration Process
    1. Stereo Calibration Video Tutorial
  6. Source

Overview

VOXL Camera Calibration is a package in voxl-suite >= 0.5.0 for calibrating cameras on-board on voxl. If you are on an older voxl-suite image, we recommend that you upgrade and use this tool, but you can find a link to the deprecated ROS calibration process below.

Use of this tool requires the ability to view the overlay image coming off of voxl. We recommend using the VOXL Web Portal to view the overlay images.

The size and spacing of the chessboard is configurable on the command line. Internally, ModalAI uses a 5x6 with 65.5mm spacing on a stiff, foam-backed board with matte finish to reduce glare. This is the default used by the calibrator tool unless a different size and spacing is set.

Note that the size is based on OpenCV’s definition of a chessboard and matches the ROS calibrator tool. That is to say, the size (4x7, 5x6, etc) is the count of the number of inner corners which is what is actually being detected by the algorithm (not number of squares). This is usually #squares-1 noting that partial outer squares are okay. A white border around the chessboard make the detector more robust and tolerant to lighting. This is one of the 5x6 chessboards used at ModalAI:

5x6_chessboard_small

Here is an image for a 6x9: https://raw.githubusercontent.com/opencv/opencv/4.x/doc/pattern.png


Command Line Options

Short OptionLong OptionEffect
-e--extrinsics-onlyFor a stereo pair, pull an existing intrinsics file and only run extrinsics
-f--fisheye Tells opencv to use fisheye parameters for finding the board and calibrating
-h--help Prints this help information
-l--length Specify the edge length of a single square in meters (default 0.0655
-m--mirror Mirror the overlay output, this is just personal preference
-s--size Specify the number of corners for the calibrator to look for (default 5x6)
-t--threshold Display the thresholded image in the overlay (debug tool for lighting conditions)

VOXL and VOXL Flight

Example using a 6x8 Checkerboard with 0.038m Squares

Tracking:

voxl2:/$ voxl-calibrate-camera tracking -f -s 6x8 -l 0.038

or

Stereo:

voxl2:/$ voxl-calibrate-camera stereo -s 6x8 -l 0.038

VOXL 2 and RB5 Flight

Example using a 6x8 Checkerboard with 0.038m Squares

Tracking:

voxl2:/$ voxl-calibrate-camera tracking -f -s 6x8 -l 0.038

or

Front Stereo:

voxl2:/$ voxl-calibrate-camera stereo_front -s 6x8 -l 0.038

or

Rear Stereo:

voxl2:/$ voxl-calibrate-camera stereo_rear -s 6x8 -l 0.038

Monocular Calibration Process

To calibrate a monocular camera, such as the tracking camera on voxl, you can simply run the command: voxl-calibrate-camera tracking --fisheye, open the web portal, and fill the rectangles like such:

Tracking Cal

Once you’ve filled all the rectangles, the calibration will run, which will take a few seconds, and then the calibration will be printed to the terminal window. If the calibration was successful, it will also write to /data/modalai/opencv_{camera-name}_intrinsics.yml

voxl2:/$ voxl-calibrate-camera tracking -f
Matrix
[277.7090664510777, 0, 290.6865358454301;
 0, 277.5687125242331, 240.1597738541476;
 0, 0, 1]
Distortion
[-0.006319990900085937;
 0.00155893534296691;
 0;
 0]
distortion_model: fisheye
Re-projection error reported by calibrateCamera: 0.172684
Calibration Succeded!

Writing data to: /data/modalai/opencv_tracking_intrinsics.yml
Saved!
Exiting Cleanly

NOTE:

When calibrating the standard OV7251 Tracking Camera, make sure to use the -f or --fisheye flag to make sure that the calibrator uses the fisheye lens distortion model.


Stereo Calibration Process

To calibrate a stereo camera, you can simply run the command: voxl-calibrate-camera stereo, open the web portal, and fill the rectangles like such:

Stereo Cal

The stereo calibrator calculates the intrinsics for each camera separately, so you will need to fill in all of the left rectangles, then all of the right rectangles. Once the intrinsics are done, you will have to manually add the extrinsic samples. To do so, hit enter in the terminal window that is running the calibrator to take a frame, once you have enough frames, type stop. These images do not have pre-specified locations since different orientations lead to different requirements. It is STRONGLY recommended that you do 2 images for the extrinsics, one skewed image on either side of the frame, like such:

Stereo Cal Left Stereo Cal Right

If everything has been done properly, you will see output like this:

voxl2:/$ voxl-calibrate-camera stereo
Sampling overlapping images now
Enter an empty line to take a sample or "stop" to finish sampling

Taking Frame

Taking Frame
stop
Stopping sampling
Calibrating Left Camera
Matrix
[493.7322756669245, 0, 306.7896643027532;
 0, 493.1380517350153, 217.4680594645219;
 0, 0, 1]
Distortion
[-0.1698366125016952;
 0.06988854948207439;
 -0.001138684086637882;
 -0.0007932118450081079;
 0]
distortion_model: plumb_bob
Re-projection error reported by calibrateCamera: 0.177678
Calibration Succeded!
Calibrating Right Camera
Matrix
[496.1483207581481, 0, 320.9542358074322;
 0, 495.5756728109903, 223.7654477880258;
 0, 0, 1]
Distortion
[-0.1725992238299667;
 0.06664783196280108;
 -0.00172072316840736;
 -0.0004606934467252117;
 0]
distortion_model: plumb_bob
Re-projection error reported by calibrateCamera: 0.179598
Calibration Succeded!
Calibrating Extrinsics
2 frames will be processed
R
[0.999777546053251, -0.0004080345076243199, 0.02108771954432934;
 0.002055883177889161, 0.9969371281114418, -0.07818015053240687;
 -0.02099123036171473, 0.07820611293723473, 0.9967161943839129]
T
[-0.08011754799309605;
 -0.001690038045698758;
 -0.0008435695774040179]
Re-projection error reported by stereoCalibrate: 0.259720
Extrinsics Calibration Succeded!

Saved intrinsics to: /data/modalai/opencv_stereo_intrinsics.yml
Saved extrinsics to: /data/modalai/opencv_stereo_extrinsics.yml
Exiting Cleanly

Stereo Calibration Video Tutorial

Source

Source code available on Gitlab.