Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
Tutorial: Camera intrinsic 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. $k_{ud}$ is the distortion parameter used to transform the coordinates from undistorted to distorted images, while $k_{du}$ is used to transform the coordinates from distorted to undistorted images.
Note
It may be useful to make a tour in Tutorial: Bridge over OpenCV that makes in relation the camera model used in ViSP with the one proposed by OpenCV.
Note also 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.

Recommendations

The following recommendation should be taken into account to obtain good results:

  • Use a rigid planar calibration board, a printed sheet is not ideal
  • Adjust the lens to get focused images and adjust the camera parameters to have good illumination
  • Avoid perpendicular images (in other terms image plane parallel to the calibration grid) since there is an ambiguity between the camera position and the focal lens
  • Take oblique images w.r.t. the calibration pattern
  • During data acquisition try to fill the images with corners keeping the whole grid in the image. It is very important to have points close to the edges and the corners of the image in order to get a better estimate of the distortion coefficients
  • Acquire between 5 and 15 images. There is no need to acquire a lot of images, but rather good poses

How to improve calibration accuracy:

  • Camera calibration is a trial and error process
  • The first run should allow to identify and remove blurred images, or images where corners are not accurately extracted
  • Exclude images that have high reprojection errors and re-calibrate

Prerequisites

1. Download and print, one of the following calibration grid

2. Stick the printed grid on a rigid support

3. Acquire images of the calibration grid

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.

To this end see Tutorial: Image frame grabbing and use one of the binaries that could be found in tutorial/grabber folder to grab single shot images of the grid.

For example, with a webcam connected to a laptop running Linux (Ubuntu, Fedora...) use one of the following:

./tutorial-grabber-v4l2 --seqname chessboard-%02d.jpg --record 1
./tutorial-grabber-opencv --seqname chessboard-%02d.jpg --record 1

If you have rather a PointGrey camera use one of the following:

./tutorial-grabber-1394 --seqname chessboard-%02d.jpg --record 1
./tutorial-grabber-flycapture --seqname chessboard-%02d.jpg --record 1

If you have rather a firewire camera that doesn't come from PointGrey use one of the following:

./tutorial-grabber-1394 --seqname chessboard-%02d.jpg --record 1
./tutorial-grabber-opencv --seqname chessboard-%02d.jpg --record 1

If you have a Basler camera use rather:

./tutorial-grabber-basler-pylon --seqname chessboard-%02d.jpg --record 1

If you have a Realsense camera use rather:

./tutorial-grabber-realsense --seqname chessboard-%02d.jpg --record 1

If you have an Occipital Structure Core camera use rather:

./tutorial-grabber-structure-core --seqname chessboard-%02d.jpg --record 1

If you have a Parrot Bebop 2 drone camera use rather:

./tutorial-grabber-bebop2 --seqname chessboard-%02d.jpg --record 1

or, if you want to calibrate the camera for HD 720p usage :

./tutorial-grabber-bebop2 --seqname chessboard-%02d.jpg --record 1 --hd_resolution

In all other cases, try with:

./tutorial-grabber-opencv --seqname chessboard-%02d.jpg --record 1

Calibration

Source code

All the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command:

$ svn export https://github.com/lagadic/visp.git/trunk/example/calibration

The calibration tool is available in calibrate_camera.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 circles 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.

With 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. A set of 13 images extracted from OpenCV dataset are provided chessboard-01.jpg, chessboard-02.jpg, ..., chessboard-13.jpg. Hereafter we give an example of one of these images.

img-chessboard-01.jpg
Snapshot example of the 9 by 6 chessboard used to calibrate the camera.

Before starting the calibration we need to create a configuration file. We create default-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: chessboard-%02d.jpg

# Tempo in seconds between two images. If > 10 wait a click to continue
Tempo: 1
Note
The images and the configuration file used in this tutorial are available in ViSP source code and copied in the same folder than the calibrate_camera binary.

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

./calibrate-camera default-chessboard.cfg

This command will produce the following output:

$ ./calibrate-camera default-chessboard.cfg 
Settings from config file: default-chessboard.cfg
grid width : 9
grid height: 6
square size: 0.025
pattern    : CHESSBOARD
input seq  : chessboard-%02d.jpg
tempo      : 1

Settings from command line options: 
Ouput xml file : camera.xml
Camera name    : Camera
Initialize camera parameters with default values 
Camera parameters used for initialization:
Camera parameters for perspective projection without distortion:
  px = 600   py = 600
  u0 = 320   v0 = 240

Process frame: chessboard-01.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-02.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-03.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-04.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-05.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-06.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-07.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-08.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-09.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-10.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-11.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-12.jpg, grid detection status: 1, image used as input data
Process frame: chessboard-13.jpg, grid detection status: 1, image used as input data

Calibration without distortion in progress on 13 images...
Camera parameters for perspective projection without distortion:
  px = 557.2519329   py = 561.1776205
  u0 = 360.0754485   v0 = 235.5240362

Image chessboard-01.jpg reprojection error: 1.230158891
Image chessboard-02.jpg reprojection error: 1.447042293
Image chessboard-03.jpg reprojection error: 2.078525011
Image chessboard-04.jpg reprojection error: 1.553888654
Image chessboard-05.jpg reprojection error: 1.697849369
Image chessboard-06.jpg reprojection error: 2.284910081
Image chessboard-07.jpg reprojection error: 1.387893707
Image chessboard-08.jpg reprojection error: 1.664988951
Image chessboard-09.jpg reprojection error: 0.9447032921
Image chessboard-10.jpg reprojection error: 1.258540894
Image chessboard-11.jpg reprojection error: 1.845113925
Image chessboard-12.jpg reprojection error: 0.8621449347
Image chessboard-13.jpg reprojection error: 1.254269691

Global reprojection error: 1.552697985
Camera parameters without distortion successfully saved in "camera.xml"


Calibration with distortion in progress on 13 images...
Camera parameters for perspective projection with distortion:
  px = 536.982404    py = 537.4196388
  u0 = 344.0958214   v0 = 235.1792108
  kud = -0.2672672093
  kdu = 0.3081092949

Image chessboard-01.jpg reprojection error: 0.2395321578
Image chessboard-02.jpg reprojection error: 1.238545486
Image chessboard-03.jpg reprojection error: 0.3207755448
Image chessboard-04.jpg reprojection error: 0.2601958886
Image chessboard-05.jpg reprojection error: 0.2338664574
Image chessboard-06.jpg reprojection error: 0.3297641256
Image chessboard-07.jpg reprojection error: 0.2475833215
Image chessboard-08.jpg reprojection error: 0.2602460339
Image chessboard-09.jpg reprojection error: 0.3159699755
Image chessboard-10.jpg reprojection error: 0.198531964
Image chessboard-11.jpg reprojection error: 0.2287278629
Image chessboard-12.jpg reprojection error: 0.406199404
Image chessboard-13.jpg reprojection error: 0.1950310138

Global reprojection error: 0.4338765096
...
Found camera with name: "Camera"
Camera parameters without distortion successfully saved in "camera.xml"

Estimated pose using vpPoseVector format: [tx ty tz tux tuy tuz] with translation in meter and rotation in rad
Estimated pose on input data extracted from chessboard-01.jpg: -0.07660266271  -0.1085728703  0.4003484889  0.1682345774  0.2703219136  0.01344238413
Estimated pose on input data extracted from chessboard-02.jpg: -0.0597725773  0.08323149726  0.3540361653  0.4146214603  0.6466739629  -1.33632262
Estimated pose on input data extracted from chessboard-03.jpg: -0.0409369733  -0.1000680319  0.3187341271  -0.2814821404  0.181607087  0.354472929
Estimated pose on input data extracted from chessboard-04.jpg: -0.09952644787  -0.06700101163  0.3311921983  -0.1147265218  0.2351468125  -0.002270637719
Estimated pose on input data extracted from chessboard-05.jpg: 0.05741410545  -0.1148693995  0.3181348172  -0.2976648906  0.4269115417  1.311802711
Estimated pose on input data extracted from chessboard-06.jpg: 0.1661888244  -0.06524589624  0.338088106  0.4034420756  0.3039782719  1.64940724
Estimated pose on input data extracted from chessboard-07.jpg: 0.01821370536  -0.07151589851  0.3905543438  0.172544729  0.3466769676  1.86809415
Estimated pose on input data extracted from chessboard-08.jpg: 0.07798259969  -0.08758717052  0.3176589755  -0.09716654268  0.4802856194  1.752367718
Estimated pose on input data extracted from chessboard-09.jpg: -0.06737515848  -0.08078390458  0.2789852517  0.2019376892  -0.4259504159  0.1328986678
Estimated pose on input data extracted from chessboard-10.jpg: 0.04573124363  -0.1106681366  0.3391361625  -0.422722622  -0.5001185984  1.335604951
Estimated pose on input data extracted from chessboard-11.jpg: 0.04966729888  -0.1021952921  0.3230817897  -0.244202703  0.3486826514  1.529624327
Estimated pose on input data extracted from chessboard-12.jpg: 0.0326829825  -0.09134603223  0.2922525995  0.4616839947  -0.2854700243  1.239441135
Estimated pose on input data extracted from chessboard-13.jpg: 0.04392199094  -0.1078950481  0.3135404232  -0.1733990329  -0.4713258735  1.346433873

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

With a circles grid

In this section we consider the ViSP symmetric circles 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 5 images called circles-01.jpg, circles-02.jpg, ..., circles-05.jpg. Hereafter we give an example of such an image.

img-circles-grid-02.jpg
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 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: circles-%02d.jpg

# Tempo in seconds between two images. If > 10 wait a click to continue
Tempo: 1
Note
The images and the configuration file used in this tutorial are available in ViSP source code and copied in the same folder than the calibrate_camera binary.

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

./calibrate-camera circles-grid.cfg

This command will produce the following output:

Settings from config file: default-circles.cfg
grid width : 6
grid height: 6
square size: 0.034
pattern    : CIRCLES_GRID
input seq  : circles-%02d.jpg
tempo      : 1

Settings from command line options: 
Ouput xml file : camera.xml
Camera name    : Camera
Initialize camera parameters with default values 
Camera parameters used for initialization:
Camera parameters for perspective projection without distortion:
  px = 600   py = 600
  u0 = 160   v0 = 120

Process frame: circles-01.jpg, grid detection status: 1, image used as input data
Process frame: circles-02.jpg, grid detection status: 1, image used as input data
Process frame: circles-03.jpg, grid detection status: 1, image used as input data
Process frame: circles-04.jpg, grid detection status: 1, image used as input data
Process frame: circles-05.jpg, grid detection status: 1, image used as input data

Calibration without distortion in progress on 5 images...
Camera parameters for perspective projection without distortion:
  px = 276.509794    py = 272.9594743
  u0 = 163.8652259   v0 = 113.304585

Image circles-01.jpg reprojection error: 0.3209792813
Image circles-02.jpg reprojection error: 0.3419007802
Image circles-03.jpg reprojection error: 0.2587615953
Image circles-04.jpg reprojection error: 0.3582072187
Image circles-05.jpg reprojection error: 0.3439095173

Global reprojection error: 0.3266397322
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 = 272.3968612   py = 268.6672142
  u0 = 163.1810262   v0 = 112.9659689
  kud = 0.03120756464
  kdu = -0.03087352596

Image circles-01.jpg reprojection error: 0.2719452401
Image circles-02.jpg reprojection error: 0.3083295554
Image circles-03.jpg reprojection error: 0.2845516993
Image circles-04.jpg reprojection error: 0.3456180431
Image circles-05.jpg reprojection error: 0.2883152857

Global reprojection error: 0.3008977558
...
Found camera with name: "Camera"
Camera parameters without distortion successfully saved in "camera.xml"

Estimated pose using vpPoseVector format: [tx ty tz tux tuy tuz] with translation in meter and rotation in rad
Estimated pose on input data extracted from circles-01.jpg: -0.08869815386  -0.07574169202  0.2543876665  0.00932552619  -0.1161670753  -0.06219301328
Estimated pose on input data extracted from circles-02.jpg: -0.03019947783  -0.07794008289  0.2265663076  0.04377113126  -0.474098285  0.09585559142
Estimated pose on input data extracted from circles-03.jpg: 0.02769610929  -0.08077604598  0.2414334564  0.2539091133  -0.4686503508  0.5745637311
Estimated pose on input data extracted from circles-04.jpg: -0.08516211221  -0.05523338957  0.2161552622  0.4338264761  -0.01669390893  -0.01146784849
Estimated pose on input data extracted from circles-05.jpg: -0.1103329039  -0.08543524482  0.268237962  0.4130501665  0.1926353241  0.2736078902

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

Analysis tools

Since ViSP 3.3.1 we provide a set of tools to analyse calibration results.

Grid patterns

Running calibrate-camera binary allows to visualize the locations of the calibration patterns in the image:

img-grid-patterns.png

A good calibration is obtained when the patterns cover most part of the image.

Reprojection error

Reprojection error could be seen in the next image. It shows the current reprojection error, the extracted points and the projected points using the estimated cMo camera pose and camera parameters:

img-calib-reprojection-error.jpg

On the console, the global reprojection error is also given for the model without distorsion parameters:

Calibration without distortion in progress on 13 images...
Camera parameters for perspective projection without distortion:
  px = 557.2519329   py = 561.1776205
  u0 = 360.0754485   v0 = 235.5240362

Image chessboard-01.jpg reprojection error: 1.230158891
Image chessboard-02.jpg reprojection error: 1.447042293
Image chessboard-03.jpg reprojection error: 2.078525011
Image chessboard-04.jpg reprojection error: 1.553888654
Image chessboard-05.jpg reprojection error: 1.697849369
Image chessboard-06.jpg reprojection error: 2.284910081
Image chessboard-07.jpg reprojection error: 1.387893707
Image chessboard-08.jpg reprojection error: 1.664988951
Image chessboard-09.jpg reprojection error: 0.9447032921
Image chessboard-10.jpg reprojection error: 1.258540894
Image chessboard-11.jpg reprojection error: 1.845113925
Image chessboard-12.jpg reprojection error: 0.8621449347
Image chessboard-13.jpg reprojection error: 1.254269691

Global reprojection error: 1.552697985

and for the model with both distorsion parameters:

Calibration with distortion in progress on 13 images...
Camera parameters for perspective projection with distortion:
  px = 536.982404    py = 537.4196388
  u0 = 344.0958214   v0 = 235.1792108
  kud = -0.2672672093
  kdu = 0.3081092949

Image chessboard-01.jpg reprojection error: 0.2395321578
Image chessboard-02.jpg reprojection error: 1.238545486
Image chessboard-03.jpg reprojection error: 0.3207755448
Image chessboard-04.jpg reprojection error: 0.2601958886
Image chessboard-05.jpg reprojection error: 0.2338664574
Image chessboard-06.jpg reprojection error: 0.3297641256
Image chessboard-07.jpg reprojection error: 0.2475833215
Image chessboard-08.jpg reprojection error: 0.2602460339
Image chessboard-09.jpg reprojection error: 0.3159699755
Image chessboard-10.jpg reprojection error: 0.198531964
Image chessboard-11.jpg reprojection error: 0.2287278629
Image chessboard-12.jpg reprojection error: 0.406199404
Image chessboard-13.jpg reprojection error: 0.1950310138

Global reprojection error: 0.4338765096

A good calibration is obtained when extracted and reprojected points are very close each other and when global reprojection error is less than 1.0. Smaller is the reprojection error, better is the calibration.

Line fitting

To get an idea on how much there is distortion, calibrate-camera binary generates also the following images:

  • left image: draw lines starting from the first and last points using points findChessboardCorners() function from OpenCV. This should allow seeing how distorted is the image.
  • right image: image is undistorted, chessboard points are extracted and lines starting from the first and last points are drawn
img-calib-line-fitting.jpg

On the console, mean distance errors for line fitting for points extracted from distorted image and after using vpPixelMeterConversion::convertPoint() is given:

This tool computes the line fitting error (mean distance error) on image points extracted from the raw distorted image.
chessboard-03.jpg line 1 fitting error on distorted points: 1.524931112 ; on undistorted points: 0.2997221937
chessboard-03.jpg line 2 fitting error on distorted points: 1.161437677 ; on undistorted points: 0.1608990656
chessboard-03.jpg line 3 fitting error on distorted points: 0.7274089743 ; on undistorted points: 0.1089682074
chessboard-03.jpg line 4 fitting error on distorted points: 0.2495991137 ; on undistorted points: 0.0648610129
chessboard-03.jpg line 5 fitting error on distorted points: 0.2932864898 ; on undistorted points: 0.07897041729
chessboard-03.jpg line 6 fitting error on distorted points: 0.9474403828 ; on undistorted points: 0.03407551552

Mean distance errors for line fitting for points extracted from undistorted image is also printed on the console:

This tool computes the line fitting error (mean distance error) on image points extracted from the undistorted image (vpImageTools::undistort()).
chessboard-03.jpg undistorted image, line 1 fitting error: 0.0840157388
chessboard-03.jpg undistorted image, line 2 fitting error: 0.09982399891
chessboard-03.jpg undistorted image, line 3 fitting error: 0.07813388194
chessboard-03.jpg undistorted image, line 4 fitting error: 0.08870325502
chessboard-03.jpg undistorted image, line 5 fitting error: 0.08680507551
chessboard-03.jpg undistorted image, line 6 fitting error: 0.06309999164

Camera poses

There is camera_calibration_show_extrinsics.py script that allows to display camera poses. Prior to use that script, you need to install scipy:

$ sudo apt install python-pip
$ pip install scipy

To visualize camera poses used for calibration, run:

$ python camera_calibration_show_extrinsics.py --calibration camera.xml --scale_focal 20

It reads the camera poses saved in camera.xml file and display them with respect to the calibration grid considered as static.

img-calib-script-extrinsic.jpg

How to get over calibration error

The non linear algorithm used for calibration needs an initialization. By default the parameters used as initial guess are the one set in vpCameraParameters default constructor for px and py, while u0 and v0 are set to the image center coordinates. When images are near HD resolution or larger, or when the focal lens is large, this initial guess may be too far from the solution to make the algorithm converging. This behavior is illustrated below:

$ ./calibrate-camera chessboard.cfg
Settings from config file: chessboard.cfg
grid width : 9
grid height: 8
square size: 0.002
pattern    : CHESSBOARD
input seq  : image%01d.png
tempo      : 1

Settings from command line options: 
Ouput xml file : camera.xml
Camera name    : Camera
Initialize camera parameters with default values 
Camera parameters used for initialization:
Camera parameters for perspective projection without distortion:
  px = 600   py = 600
  u0 = 640   v0 = 512

Process frame: image1.png, grid detection status: 1, image used as input data
frame: image1.png, unable to calibrate from single image, image rejected
Process frame: image2.png, grid detection status: 1, image used as input data
frame: image2.png, unable to calibrate from single image, image rejected
Unable to calibrate. Image processing failed !

The work around is here to give an initial guess not so far from the solution so that it allows the algorithm to converge.

This initial guess is to set in an xml file, like here in camera-init.xml file:

$ more camera-init.xml
<?xml version="1.0"?>
<root>
  <camera>
    <name>Camera</name>
    <image_width>1080</image_width>
    <image_height>1440</image_height>
    <model>
      <type>perspectiveProjWithoutDistortion</type>
      <!--Pixel ratio-->
      <px>9700</px>
      <py>9700</py>
      <!--Principal point-->
      <u0>540</u0>
      <v0>720</v0>
    </model>
  </camera>
</root>

We set the image size, u0 and v0 to the image center coordinates, and px = py = 9700.

Now to use this file as initial guess, run:

$ calibrate-camera chessboard.cfg --init-from-xml camera-init.xml --camera-name Camera

It shows that the algorithm is now able to estimate the parameters:

Settings from config file: chessboard.cfg
grid width : 9
grid height: 8
square size: 0.002
pattern    : CHESSBOARD
input seq  : image%01d.png
tempo      : 1

Settings from command line options: 
Init parameters: camera-init.xml
Ouput xml file : camera.xml
Camera name    : Camera
Initialize camera parameters from xml file: camera-init.xml
Found camera with name: "Camera"
Camera parameters used for initialization:
Camera parameters for perspective projection without distortion:
  px = 9700  py = 9700
  u0 = 540   v0 = 720

Process frame: image1.png, grid detection status: 1, image used as input data
Process frame: image2.png, grid detection status: 1, image used as input data

Calibration without distortion in progress on 2 images...
Camera parameters for perspective projection without distortion:
  px = 9654.217159   py = 9667.966935
  u0 = 650.2304211   v0 = 519.018459

Image image1.png reprojection error: 0.8274370565
Image image2.png reprojection error: 0.6922641507

Global reprojection error: 0.7628504889
Camera parameters without distortion successfully saved in "camera.xml"

Distorsion removal

Once the camera is calibrated, you can remove distortion in an image to generate an undistorted image.

Undistort a single image

The following example available in tutorial-undistort.cpp shows how to do it.

#include <visp3/core/vpImageTools.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/core/vpXmlParserCamera.h>
#include <visp3/io/vpImageIo.h>
int
main( int argc, char **argv )
{
std::string opt_input_image = "chessboard.jpg";
std::string opt_camera_file = "camera.xml";
std::string opt_camera_name = "Camera";
try
{
for ( int i = 1; i < argc; i++ )
{
if ( std::string( argv[i] ) == "--image" && i + 1 < argc )
{
opt_input_image = std::string( argv[i + 1] );
}
else if ( std::string( argv[i] ) == "--camera-file" && i + 1 < argc )
{
opt_camera_file = std::string( argv[i + 1] );
}
else if ( std::string( argv[i] ) == "--camera-name" && i + 1 < argc )
{
opt_camera_name = std::string( argv[i + 1] );
}
else if ( std::string( argv[i] ) == "--help" || std::string( argv[i] ) == "-h" )
{
std::cout << argv[0] << " [--image <input image (pgm,ppm,jpeg,png,tiff,bmp,ras,jp2)>]"
<< " [--camera-file <xml file>] [--camera-name <name>] [--help] [-h]\n"
<< std::endl;
std::cout << "Examples: " << std::endl
<< argv[0] << std::endl
<< argv[0] << " --image chessboard.jpg --camera-file camera.xml --camera-name Camera" << std::endl;
return EXIT_SUCCESS;
}
}
std::cout << "Read input image: " << opt_input_image << std::endl;
vpImageIo::read( I, opt_input_image );
if ( p.parse( cam, opt_camera_file, opt_camera_name, projModel, I.getWidth(), I.getHeight() ) !=
{
std::cout << "Cannot found parameters for camera named \"Camera\"" << std::endl;
}
#if 0
cam.initPersProjWithDistortion(582.7, 580.6, 326.6, 215.0, -0.3372, 0.4021);
#endif
std::cout << cam << std::endl;
vpImageTools::undistort( I, cam, Iud );
std::string name_we = vpIoTools::getNameWE( opt_input_image );
std::string ext = vpIoTools::getFileExtension( opt_input_image );
std::string output_image = name_we + "-undistort" + ext;
std::cout << "Save undistorted image in: " << output_image << std::endl;
vpImageIo::write( Iud, output_image );
}
catch ( const vpException &e )
{
std::cout << "Catch an exception: " << e << std::endl;
}
return 0;
}

In this example we first load the image chessboard.jpg

std::cout << "Read input image: " << opt_input_image << std::endl;
vpImageIo::read( I, opt_input_image );

Then we read the camera parameters with distortion of a camera named "Camera" from ./camera.xml file.

if ( p.parse( cam, opt_camera_file, opt_camera_name, projModel, I.getWidth(), I.getHeight() ) !=
{
std::cout << "Cannot found parameters for camera named \"Camera\"" << std::endl;
}

If vpXmlParserCamera is not available, we initialize the camera parameters "by hand" using the following code:

#if 0
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.jpg.

vpImageTools::undistort( I, cam, Iud );
std::string name_we = vpIoTools::getNameWE( opt_input_image );
std::string ext = vpIoTools::getFileExtension( opt_input_image );
std::string output_image = name_we + "-undistort" + ext;
std::cout << "Save undistorted image in: " << output_image << std::endl;
vpImageIo::write( Iud, output_image );

Results are shown in the next images:

  • left image is the input image chessboard.jpg
  • right image is the resulting chessboard-undistort.jpg image where distorsion is removed thanks to the camera intrinsic parameters. Here you can see that chessboard lines are straight.
img-chessboard-undistort.jpg

Undistort a sequence of images

Instead of using vpImageTools::undistort() like in tutorial-undistort.cpp, we recommend to use vpImageTools::initUndistortMap() once over the first image, and then call vpImageTools::remap() for each image.

The pseudo code is the following:

vpArray2D<int> mapU, mapV;
vpArray2D<float> mapDu, mapDv;
vpImage<unsigned char> I; // Input image
vpImage<unsigned char> Iundist; // Undistorted output image
bool init_done = false;
while (! end) {
acquire(I);
if (! init_done) {
vpImageTools::initUndistortMap(cam, I.getWidth(), I.getHeight(), mapU, mapV, mapDu, mapDv);
init_done = true;
}
vpImageTools::remap(I, mapU, mapV, mapDu, mapDv, Iundist);
}

Next tutorial

You are now ready to see the Tutorial: Camera extrinsic calibration that will explain how to estimate the eye-in-hand transformation when the camera is mounted on a robot end-effector.