Note: This tutorial assumes that you have completed the previous tutorials: Quick start guide, How to calibrate a monocular camera. |
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. |
Intrinsic calibration of the Kinect cameras
Description: This tutorial shows how to calibrate the intrinsic parameters of the IR (depth) and RGB cameras, including focal length and the distortion model. For applications requiring high accuracy, calibration can improve on the default camera models used by openni_camera. This calibration does not necessary fully calibrate the depth. Especially the ASUS Xtion is prone to depth errors and needs further calibration (see also here and here). There is no official module in ROS yet to calibrate this (as of 6th February 2015).Tutorial Level: BEGINNER
Should I calibrate?
Not necessarily. The openni_camera driver provides default camera models out-of-the-box with reasonably accurate focal lengths (relating 3D points to 2D image coordinates). They do not model lens distortion, but fortunately the Kinect uses low-distortion lenses (|k1| ~= 0.1), so even the edges of the image are not displaced by more than a few pixels.
If your application requires maximum accuracy from the Kinect's 3D data, however, performing a rigorous calibration is helpful.
RGB camera
Bring up the OpenNI driver:
roslaunch openni_launch openni.launch
Now follow the standard monocular camera calibration instructions. Use the following command (substituting the correct dimensions of your checkerboard):
rosrun camera_calibration cameracalibrator.py image:=/camera/rgb/image_raw camera:=/camera/rgb --size 5x4 --square 0.0245
Don't forget to Commit your successful calibration.
IR (depth) camera
The Kinect detects depth by using an IR camera and IR speckle projector as a pseudo-stereo pair. We will calibrate the "depth" camera by detecting checkerboards in the IR image, just as we calibrated the RGB camera.
The speckle pattern makes it impossible to detect the checkerboard corners accurately in the IR image. The simplest solution is to cover the projector (lone opening on the far left) with one or two Post-it notes, mostly diffusing the speckles. An ideal solution is to block the projector completely and provide a separate IR light source. Good illumination sources include sunlight, halogen lamps, or incandescent lamps.
IR with speckle pattern |
IR with projector covered by Post-it note |
As before, follow the monocular camera calibration instructions:
rosrun camera_calibration cameracalibrator.py image:=/camera/ir/image_raw camera:=/camera/ir --size 5x4 --square 0.0245
The Kinect camera driver cannot stream both IR and RGB images. It will decide which of the two to stream based on the amount of subscribers, so kill nodes that subscribe to RGB images before doing the IR calibration.
Don't forget to Commit your successful calibration.
Where are the intrinsics saved?
When you click Commit, cameracalibrator.py sends the new calibration to the camera driver as a service call. The driver immediately begins publishing the updated calibration on its camera_info topic.
openni_camera uses camera_info_manager to manage calibration parameters. By default, it saves intrinsics to $HOME/.ros/camera_info/NAME.yaml and identifies them by the device serial number:
$ ls ~/.ros/camera_info/ depth_B00362708888047B.yaml rgb_B00362708888047B.yaml
Whenever you bring up the OpenNI driver, it will look for a previously saved calibration. If you want to share the intrinsics among multiple users, move them somewhere public (e.g. /public/path/) and use a launch file which configures the camera info URLs:
<launch> <!-- Include official launch file and specify camera_info urls --> <include file="$(find openni_launch)/launch/openni.launch"> <!-- provide arguments to that launch file --> <arg name="rgb_camera_info_url" value="file:///public/path/rgb_B00362708888047B.yaml" /> <arg name="depth_camera_info_url" value="file:///public/path/depth_B00362708888047B.yaml" /> </include> </launch>