ViSP  2.8.0
Tutorial: Camera calibration

This tutorial focuses on pinhole camera calibration. The goal of the calibration is here to estimate some camera parameters that allows to make the relation between camera's natural units (pixel positions in the image) and real world units (normalized position in meters in the image plane).

Introduction

If we denote $(u,v)$ the position of a pixel in the digitized image, this position is related to the corresponding coordinates $(x,y)$ in the normalized space.

In ViSP we consider two unit conversions:

  • From meters to pixels we consider the following formula:

    \[ \begin{array}{l} u = u_0 + x p_x (1+k_{ud} r^2) \\ v = v_0 + y p_y (1+k_{ud} r^2) \end{array} \]

    with $ r^2 = x^2+y^2 $
  • From pixels to meters we consider the following formula:

    \[ \begin{array}{l} x = (u-u_0)*(1+k_{du} r^2)/p_x \\ y = (v-v_0)*(1+k_{du} r^2)/p_y \end{array} \]

    with $ r^2=((u - u_0)/p_x)^2+((v-v_0)/p_y)^2 $

In this model we consider the parameters $(u_0,v_0,p_x,p_y, k_{ud}, k_{du})$ where:

  • $(u_0, v_0)$ are the coordinates of the principal point in pixel;
  • $(p_x, p_y)$ are the ratio between the focal length and the size of a pixel;
  • $(k_{ud}, k_{du})$ are the parameters used to correct the distortion.

Note that the container dedicated to camera parameters is implemented in the vpCameraParameters class. It allows to consider two kind of models; with or without distortion.

The calibration process allows to estimate the values of these parameters. To this end, one of the following calibration grid can be used:

To calibrate your camera you need to take snapshots of one of these two patterns with your camera. At least 5 good snapshots of the input pattern acquired at different positions are requested for good results.

Source code

The source code of the calibration tool is available in camera_calibration.cpp located in example/calibration folder.

We will not describe in detail the source, but just mention that:

  • the image processing is performed using OpenCV;
  • the estimation of the parameters is done using a virtual visual servoing scheme;
  • the calibration tool takes as input a configuration file that allows to precise the kind of pattern used in the images (chessboard or circle grid), and the location of the images used as input. If libjpeg and libpng 3rd party libraries are installed and detected during ViSP configuration, you may consider .pgm, .ppm, .jpg, .png images. Default configuration files are provided in example/calibration folder;
  • the resulting parameters are saved in camera.xml file.

Calibration from a chessboard

In this section we consider the OpenCV chessboard pattern that has a size of 9 by 6. Each square of the chessboard is 0.025 meters large. We took 5 images called chessboard-01.png, chessboard-02.png, chessboard-03.png, chessboard-04.png, chessboard-05.png. Hereafter we give an example of such an image. These images are located in /tmp folder.

img-chessboard-01.png
Snapshot example of the chessboard used to calibrate the camera.

Before starting the calibration we need to create a configuration file. We create /tmp/chessboard.cfg with the following content:

# Number of inner corners per a item row and column. (square, circle)
BoardSize_Width: 9
BoardSize_Height: 6
# The size of a square in meters
Square_Size: 0.025
# The type of pattern used for camera calibration.
# One of: CHESSBOARD or CIRCLES_GRID
Calibrate_Pattern: CHESSBOARD
# The input image sequence to use for calibration
Input: /tmp/chessboard-%02d.png

To estimate the camera parameters, just enter in ViSP <binary_dir>/examples/calibration and run:

./camera_calibration /tmp/chessboard.cfg

This command will produce the following output:

grid width : 9
grid height: 6
square size: 0.025
pattern : CHESSBOARD
input seq : /tmp/chessboard-%02d.png
frame: 1 status: 1
frame: 2 status: 1
frame: 3 status: 1
frame: 4 status: 1
frame: 5 status: 1
Calibration without distortion in progress on 5 images...
Camera parameters for perspective projection without distortion:
px = 547.3080992 py = 546.9825167
u0 = 324.6299338 v0 = 229.9072033
Global reprojection error: 2.632851934
Camera parameters without distortion successfully saved in "camera.xml"
Calibration with distortion in progress on 5 images...
Camera parameters for perspective projection with distortion:
px = 582.7521622 py = 580.6586412
u0 = 326.5736348 v0 = 214.9591392
kud = -0.3372254753
kdu = 0.4021511255
Global reprojection error: 0.6350883328
Camera parameters without distortion successfully saved in "camera.xml"

The resulting parameters are also saved in ./camera.xml file.

Calibration from a circle grid

In this section we consider the ViSP symmetric circle grid pattern that has a size of 6 by 6. Each circle center of gravity is 0.034 meters distant from it's horizontal or vertical neighbor. We took 6 images called circles-02.pgm, circles-03.pgm, ..., circles-07.pgm. Hereafter we give an example of such an image. These images are located in /tmp folder.

img-circles-grid-02.png
Snapshot example of the symmetric circles grid used to calibrate the camera.

Before starting the calibration we need to create a configuration file. We create /tmp/circles-grid.cfg with the following content:

# Number of inner corners per a item row and column. (square, circle)
BoardSize_Width: 6
BoardSize_Height: 6
# The size of a square in meters
Square_Size: 0.034
# The type of pattern used for camera calibration.
# One of: CHESSBOARD or CIRCLES_GRID
Calibrate_Pattern: CIRCLES_GRID
# The input image sequence to use for calibration
Input: /tmp/circles-%02d.pgm

To estimate the camera parameters, just enter in ViSP <binary_dir>/examples/calibration and run:

./camera_calibration /tmp/circles-grid.cfg

This command will produce the following output:

grid width : 6
grid height: 6
square size: 0.034
pattern : CIRCLES_GRID
input seq : /tmp/circles-%02d.pgm
frame: 2 status: 1
frame: 3 status: 1
frame: 4 status: 1
frame: 5 status: 0
frame: 6 status: 1
frame: 7 status: 1
Calibration without distortion in progress on 6 images...
Camera parameters for perspective projection without distortion:
px = 552.4774691 py = 544.8066862
u0 = 308.732533 v0 = 245.8146982
Global reprojection error: 0.2888553796
Camera parameters without distortion successfully saved in "camera.xml"
Calibration with distortion in progress on 6 images...
Camera parameters for perspective projection with distortion:
px = 550.9009948 py = 543.1425164
u0 = 309.1726232 v0 = 245.7667949
kud = 0.01091468479
kdu = -0.01088523009
Global reprojection error: 0.2763660773
Camera parameters without distortion successfully saved in "camera.xml"

The resulting parameters are also saved in ./camera.xml file.

Note here that the following line indicates that the 5th frame corresponding to the image circles-05.pgm was not used in the calibration process since the status of the image processing is false.

frame: 5 status: 0

Distorsion removal

Once the camera is calibrated, you can remove the distortion in the images. The following example available in tutorial-undistort.cpp shows how to do it.

#include <visp/vpImageIo.h>
#include <visp/vpImageTools.h>
#include <visp/vpXmlParserCamera.h>
int main()
{
vpImageIo::read(I, "chessboard.pgm");
#ifdef VISP_HAVE_XML2
if (p.parse(cam, "camera.xml", "Camera", projModel, I.getWidth(), I.getHeight()) != vpXmlParserCamera::SEQUENCE_OK) {
std::cout << "Cannot found parameters for camera named \"Camera\"" << std::endl;
}
#else
cam.initPersProjWithDistortion(582.7, 580.6, 326.6, 215.0, -0.3372, 0.4021);
#endif
std::cout << cam << std::endl;
vpImageIo::write(Iud, "chessboard-undistort.pgm");
return 0;
}

In this example we first load the image chessboard.pgm

vpImageIo::read(I, "chessboard.pgm");

Then we read the camera parameters with distortion of a camera named "Camera" from ./camera.xml file. This is only possible if ViSP was build with libxml2 3rd party support.

#ifdef VISP_HAVE_XML2
if (p.parse(cam, "camera.xml", "Camera", projModel, I.getWidth(), I.getHeight()) != vpXmlParserCamera::SEQUENCE_OK) {
std::cout << "Cannot found parameters for camera named \"Camera\"" << std::endl;
}

If vpXmlParserCamera is not available (this may occur if ViSP was not build with libxml2), we initialize the camera parameters "by hand" using the following code:

#else
cam.initPersProjWithDistortion(582.7, 580.6, 326.6, 215.0, -0.3372, 0.4021);
#endif

Finally, we create a new image Iud where distortion is removed. This image is saved in chessboard-undistort.pgm.

vpImageIo::write(Iud, "chessboard-undistort.pgm");

The resulting chessboard-undistort.pgm image is the following.

img-chessboard-undistort.png
chessboard-undistort.pgm image where distortion was removed.