In this article, I’m going to calibrate a multi camera setup and I’m going to do it in a way that’s automated and reproducible.
Tools and files used in this article:
First, install the camera_calib toolbox:
git clone https://github.com/justinblaber/camera_calib.git ~/camera_calib
Next, download the example data (warning: very large file…):
mkdir -p ~/Desktop/multi_camera_calib cd ~/Desktop/multi_camera_calib wget https://justinblaber.org/downloads/articles/multi_camera_calib/multi_camera_calib.zip unzip multi_camera_calib.zip
The zip contains:
CAM_1
,CAM_2
, andCAM_3
– These contain calibration board images from individual cameras as well as yaml configuration files for multi_pyspin.MULTI
– This contains multi-camera synchronized capture of a calibration board as well as yaml configuration files for multi_pyspin.dotvision_checker.conf
– a configuration file used to specify parameters for the calibration board and algorithms used incamera_calib
.multi_camera_calib.m
– a script to perform camera calibration.
15 images were acquired individually for each camera as well as for synchronized multi-camera capture. You can verify that synchronized capture worked based on the timestamp info after the DATETIME
field in the filename. They should all be nearly ~1e-3 seconds apart at most. These images were acquired using the multi_pyspin gui. Please refer to the “acquiring synchronized multi-camera images” article for more info on how to use the app.
The camera_calib
config file, dotvision_checker.conf
, contains some required fields as well as some user overrides for some default fields:
% Checkerboard target target = checker target_optimization = edges % Checkerboard geometry height_cb = 50.8 width_cb = 50.8 num_targets_height = 16 num_targets_width = 16 target_spacing = 2.032 height_fp = 42.672 width_fp = 42.672 obj_cb_geom = class.cb_geom.csgrid_cfp % Optimization calib_optimization = distortion_refinement % Plotting camera_size = 20
These options mean the following:
target
– as of this article, “checker” and “circle” are currently supported.target_optimization
– depends on the target, but “opencv” and “edges” are currently supported for checkers.height_cb
– “height” of the calibration board. This is mainly used for setting the origin of the calibration board. It also helps with plotting functionality.width_cb
– “width” of the calibration board. This is mainly used for setting the origin of the calibration board. It also helps with plotting functionality.num_targets_height
– number of targets in the y dimension.num_targets_width
– number of targets in the x dimension.target_spacing
– space between targets.height_fp
– height of the four point fiducial marker box.width_fp
– width of the four point fiducial marker box.obj_cb_geom
– this is the calibration board geometry class. The user can write their own and plug it into the+class/+cb_geom
folder. In this case,csgrid_cfp
is a centered square grid with centered four point fiducial markers.calib_optimization
– type of calibration optimization used. Currently “distortion_refinement” and “frontal_refinement” are supported.camera_size
– purely for plotting purposes; perscribes the size of the camera in the extrinsics plot.
There are actually a lot more options… I’d suggest peeking at the code for now to see what options are available and which defaults are set. Once the toolbox is hardened a little bit I plan on writing some better documentation.
Next, fire up matlab, navigate to the multi_camera_calib
directory in the matlab terminal, add camera_calib
to your path, and then run the multi_camera_calib.m
script.
This script will demonstrate how to run an automated multi-camera calibration. It will use two methods: 1) The first method does the multi-camera calibration using the individual camera calibration instrinics found using single camera calibration and the CAM_*
images, followed by refinement of relative camera extrinsics using the MULTI
images. 2) The second method does a direct multi-camera calibration using only the MULTI
images.
Just to break things down, the first part:
calib_config = intf.load_calib_config('dotvision_checker.conf');
will load the configuration as a matlab struct.
The calib_single()
and calib_multi()
functions are mini pipelines that I’ve written to work specifically with the images acquired from multi_pyspin
and my calibration board, which contains the four fiducial markers supported by camera_calib
.
For the first method (note it may be a little slow because the images are high resolution), a lot of guis should appear. The first thing is to go through the four point detector gui:
You can flip through this gui by hitting the left and right arrow keys. You can also zoom in on individual fiducial targets using the “1”, “2”, “3”, and “4” keys. Lastly, the “worst” target can be seen by hitting the “w” key. It might be good to do a sweep through with the whole image view, then do another quick sweep with “w” as a fiducial marker detection failure will probably occur with the detected marker with the worst correlation coefficient.
Now, lets look at the calibration gui:
Again, you can flip through this gui by hitting the left and right arrow keys. You can also see the “worst” residual by hitting the “w” key. I’d again do a sweep through the images just to double check everything looks ok. The main “high level” check is that all the residuals for a camera should appear gaussian-ish, centered at zero, and should be relatively small (less than a pixel if a high quality target/camera/lens is used). Zoomed in residuals are shown below:
Another good sanity check is to view the extrinsics plot, shown below:
This looks very similar to my actual physical camera setup (shown in the multi-camera setup article). So it increases the confidence my calibration is correct
Next, the results for the second method (direct multi-camera calibration using MULTI
images only) yields relatively similar results. The resulting intrinsics and relative extrinics between the cameras for the two methods are shown below:
# Single camera intrinics with multi camera extrincs Intrinsic params (+- 3*sigma): -Camera (1): -Camera (2): -Camera (3): alpha: 3614.5728 +- 0.0000 alpha: 3644.0784 +- 0.0000 alpha: 3649.9648 +- 0.0000 x_o: 1024.7073 +- 0.0000 x_o: 1069.1871 +- 0.0000 x_o: 1093.0566 +- 0.0000 y_o: 814.8013 +- 0.0000 y_o: 810.5466 +- 0.0000 y_o: 805.6934 +- 0.0000 -Distortion (1): -Distortion (2): -Distortion (3): k1: -0.1429 +- 0.0000 k1: -0.1732 +- 0.0000 k1: -0.1789 +- 0.0000 k2: 0.0292 +- 0.0000 k2: 0.2792 +- 0.0000 k2: 0.2630 +- 0.0000 p1: 0.0004 +- 0.0000 p1: 0.0001 +- 0.0000 p1: -0.0000 +- 0.0000 p2: 0.0002 +- 0.0000 p2: 0.0005 +- 0.0000 p2: -0.0001 +- 0.0000 Relative extrinsic params (+- 3*sigma): -Rotation (1 => 1): -Rotation (1 => 2): -Rotation (1 => 3): theta_x: -0.0000 +- 0.0000 theta_x: -0.0045 +- 0.0000 theta_x: -0.0178 +- 0.0000 theta_y: -0.0000 +- 0.0000 theta_y: 0.3962 +- 0.0000 theta_y: 0.8076 +- 0.0000 theta_z: 0.0000 +- 0.0000 theta_z: -0.0012 +- 0.0000 theta_z: -0.0046 +- 0.0000 -Translation (1 => 1): -Translation (1 => 2): -Translation (1 => 3): x: 0.0000 +- 0.0000 x: -83.8707 +- 0.0047 x: -154.4280 +- 0.0050 y: 0.0000 +- 0.0000 y: 0.0509 +- 0.0035 y: 0.2126 +- 0.0036 z: 0.0000 +- 0.0000 z: -5.5244 +- 0.0038 z: 67.2451 +- 0.0064
# Multi camera intrinsics and extrinics Intrinsic params (+- 3*sigma): -Camera (1): -Camera (2): -Camera (3): alpha: 3626.3759 +- 0.7603 alpha: 3650.0801 +- 0.6046 alpha: 3646.8749 +- 0.8149 x_o: 1024.5323 +- 1.5735 x_o: 1064.8211 +- 1.1667 x_o: 1096.5898 +- 1.5530 y_o: 808.6427 +- 1.2712 y_o: 809.5807 +- 0.9578 y_o: 806.1936 +- 1.2944 -Distortion (1): -Distortion (2): -Distortion (3): k1: -0.1336 +- 0.0023 k1: -0.1727 +- 0.0018 k1: -0.1780 +- 0.0021 k2: -0.1345 +- 0.0424 k2: 0.2549 +- 0.0335 k2: 0.2964 +- 0.0285 p1: 0.0003 +- 0.0001 p1: 0.0000 +- 0.0001 p1: -0.0001 +- 0.0001 p2: 0.0001 +- 0.0001 p2: 0.0002 +- 0.0001 p2: 0.0001 +- 0.0001 Relative extrinsic params (+- 3*sigma): -Rotation (1 => 1): -Rotation (1 => 2): -Rotation (1 => 3): theta_x: 0.0000 +- 0.0000 theta_x: -0.0031 +- 0.0003 theta_x: -0.0159 +- 0.0005 theta_y: -0.0000 +- 0.0000 theta_y: 0.3975 +- 0.0005 theta_y: 0.8066 +- 0.0006 theta_z: 0.0000 +- 0.0000 theta_z: -0.0014 +- 0.0001 theta_z: -0.0045 +- 0.0004 -Translation (1 => 1): -Translation (1 => 2): -Translation (1 => 3): x: 0.0000 +- 0.0000 x: -84.1412 +- 0.0162 x: -154.9423 +- 0.0381 y: -0.0000 +- 0.0000 y: 0.0509 +- 0.0033 y: 0.2009 +- 0.0261 z: 0.0000 +- 0.0000 z: -5.7234 +- 0.0445 z: 66.5080 +- 0.0882
Both intrinsics and relative extrinsics are very similar in magnitude, although a sensitivity analysis should be done to see how big of an effect these changed have on downstream analyses.
Lastly, you can save the results with the util.save_calib()
function to store the results on disk.
Thanks for sharing post, it is very good. Have you have any idea/toolbox for calibrating two or multiple cameras without any overlap field of view?
Haven’t tried this, but I think you’ll at least need a calibration target which is visible in both cameras at the same time (even if FOV doesn’t overlap). My toolbox assumes the entire calibration target is visible in all cameras, but the application I’m interested in is 3D surface stuff so the target object should be completely visible in all cameras. Not having the constraint of the entire calibration target in the image makes fiducial detection a lot harder…