Note: This tutorial assumes that you have completed the previous tutorials: ROS Tutorials.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

How to Calibrate a Monocular Camera

Description: This tutorial cover using the camera_calibration's cameracalibrator.py node to calibrate a monocular camera with a raw image over ROS.

Keywords: monocular, camera, calibrate

Tutorial Level: BEGINNER

Before Starting

Make sure that you have the following:

  • a large checkerboard with known dimensions. This tutorial uses a 8x6 checkerboard with 108mm squares. Calibration uses the interior vertex points of the checkerboard, so an "9x7" board uses the interior vertex parameter "8x6" as in the example below.

  • a well lit 5m x 5m area clear of obstructions and check board patterns
  • a monocular camera publishing images over ROS

Compiling

Start by getting the dependencies and compiling the driver.

$ rosdep install camera_calibration

Make sure that your monocular camera is publishing images over ROS. Let's list the topics to check that the images are published:

$ rostopic list

This will show you all the topics published, check to see that there is an image_raw topic. The default topics provided by most ROS camera drivers are:

  • /camera/camera_info
    /camera/image_raw

If you have multiple cameras or are running the driver in its own namespace, your topic names may differ.

Running the Calibration Node

To start the calibration you will need to load the image topics that will be calibrated:

$ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 image:=/camera/image_raw camera:=/camera

This will open up the calibration window which will highlight the checkerboard:

  • mono_0.png

If it does not open up the window try the following parameter:

 --no-service-check

If you can't see any colored dots make sure you count the interior vertex points, not the squares!

Dual Checkerboards

New in D

Starting in Diamondback, you will be able to use multiple size checkerboards to calibrate a camera.

To use multiple checkerboards, give multiple --size and --square options for additional boards. Make sure the boards have different dimensions, so the calibration system can tell them apart.

Moving the Checkerboard

In order to get a good calibration you will need to move the checkerboard around in the camera frame such that:

  • checkerboard on the camera's left, right, top and bottom of field of view
    • X bar - left/right in field of view
    • Y bar - top/bottom in field of view
    • Size bar - toward/away and tilt from the camera
  • checkerboard filling the whole field of view
  • checkerboard tilted to the left, right, top and bottom (Skew)

At each step, hold the checkerboard still until the image is highlighted in the calibration window.

cal0007.png

cal0009.png

cal0011.png

cal0006.png

cal0008.png

cal0012.png

As you move the checkerboard around you will see three bars on the calibration sidebar increase in length. When the CALIBRATE button lights, you have enough data for calibration and can click CALIBRATE to see the results.

Calibration can take about a minute. The windows might be greyed out but just wait, it is working.

  • mono_1.png

Calibration Results

After the calibration is complete you will see the calibration results in the terminal and the calibrated image in the calibration window:

  • mono_2.png

A successful calibration will result in real-world straight edges appearing straight in the corrected image.

A failed calibration usually results in blank or unrecognizable images, or images that do not preserve straight edges.

After a successful calibration, you can use the slider at the top of the calibration window to change the size of the rectified image. A scale of 0.0 means that the image is sized so that all pixels in the rectified image are valid. The rectified image has no border, but some pixels from the original image are discarded. A scale of 1.0 means that all pixels in the original image are visible, but the rectified image has black borders where there are no input pixels in the original image.

D =  [-0.33758562758914146, 0.11161239414304096, -0.00021819272592442094, -3.029195446330518e-05]
K =  [430.21554970319971, 0.0, 306.6913434743704, 0.0, 430.53169252696676, 227.22480030078816, 0.0, 0.0, 1.0]
R =  [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P =  [1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0]
# oST version 5.0 parameters


[image]

width
640

height
480

[narrow_stereo/left]

camera matrix
430.215550 0.000000 306.691343
0.000000 430.531693 227.224800
0.000000 0.000000 1.000000

distortion
-0.337586 0.111612 -0.000218 -0.000030 0.0000

rectification
1.000000 0.000000 0.000000
0.000000 1.000000 0.000000
0.000000 0.000000 1.000000

projection
1.000000 0.000000 0.000000 0.000000
0.000000 1.000000 0.000000 0.000000
0.000000 0.000000 1.000000 0.000000

If you are satisfied with the calibration, click COMMIT to send the calibration parameters to the camera for permanent storage. The GUI exits and you should see "writing calibration data to ..." in the console.

Creating a yml file

The Camera Calibration Parser helps you to create a yml file, which you can load with nearly all ros camera driver using the camera_info_url parameter.

Rectifying an image

Simply loading a calibration file does not rectify the image. For rectification, use the image_proc package.

Wiki: camera_calibration/Tutorials/MonocularCalibration (last edited 2019-09-19 20:59:44 by rukie)