Easy Depth calibration (aka Depth Calibration for Dummies) is a complete software package for calibrating any Depth sensor (in particular RGBD cameras, such as Kinext, Xtion, etc.) with a very simple and easy-to-execute procedure.

Map acquired using an uncalibrated sensor (green is ground truth)

Map acquired using a calibrated sensor (green is ground truth)
Developers/Authors:
Maurilio Di Cicco, Giorgio Grisetti, Luca Iocchi
Paper:
Non parametric Depth calibration @ 13th Intelligent Autonomous Systems (IAS) 2014
1 2 3 4 5 6 |
@InProceedings{DiCIoGri_IAS14, author = {Di Cicco, Maurilio and Iocchi, Luca and Grisetti, Giorgio}, title = {Non-Parametric Calibration for Depth Sensors}, booktitle = {Proc. of the 13th International Conference on Intelligent Autonomous Systems. (IAS 13) }, year = {2014} } |
Source:
https://github.com/mauriliodc/easydepthcalib
Do you want to use it but you are experiencing problems?
Drop me a message! CLICK TO SHOW@dis.uniroma1.it
Hardware
The Easy Depth Calibration software has been tested on the following devices: Asus Xtion, Microsoft Kinect for Windows, Microsoft Kinect for Xbox 360
The following drivers are, at the time of writing, available:
Asus Xtion: Openni2 – ROS node
Kinect for Windows: Freenect – ROS node
Kinect for Xbox360: Openni2 – ROS node
Software needed
Dependencies needed are listed here:
PCL 1.6
OpenCV
Eigen
Ros (the package has been developed and is currently in use in our lab using Indigo and Ubuntu 14.04 LTS)
Usually with a ROS out of the box installation all the requested dependecies are automatically satisfied.
Datasets:
Some data sets that have been used to calibrate our sensors are available here.
The data is available as ROS bag files to maximize compatibility.
The bag files contains the following topics:
CAMERA/DEPTH/IMAGE_RAW
CAMERA/DEPTH/CAMERA_INFO
KINECT FOR WINDOWS
XTION(1)
XTION(2)
XTION_V2_1
XTION_V2_2
XTION_V2_3
XTION_V2_4
Calibration procedure (HOW TO)
The Easy Depth Calibration procedure usually takes only a few minutes by following the steps described below. Here, we assume an off-line calibration phase, but these steps can be easily automated on a mobile robot and run on-line.
1. Acquire a data set
Use your preferred set-up to acquire a ROS bag with depth data from your RGBD sensor.
They are usually recorded in the topics:
/camera/depth/image_raw
/camera/depth/camera_info
Example:
$rosbag record /camera/depth/image_raw /camera/depth/camera_info
If you want to test the calibration procedure with one of our data sets, please download one from the Datasets section.
Check the video to see an actual calibration procedure using an XTION camera.
2. Generate the training set
After you have the ROS bag, you can use the depthDumper node to generate the images in a standard format (PGMs) needed by the calibration stack.
Example:
[Terminal 1] $rosbag play <your_bag>
[Terminal 2] $rosrun easydepthcalib depthDumper
– default subscription topics are /camera/depth/image_raw and /camera/depth/camera_info
– you can remap using the ROS standards, like:
$rosrun easyDepthCalib depthDumper _imageTopic:=<IMAGE_TOPIC_NAME> _cameraInfoTopic:=<CAMERA_INFO_TOPIC_NAME>
– when you stop the executable, you will find in the current folder:
1) an input index file (out.mal by default) that describes the sensor (K camera info matrix, topic name, columns, rows, …) and contains the list of PGM files with depth values
2) all the depth images dumped as 16 bit PGM files
3. Generate the look-up table for the undistortion function
The look-up table of the undistortion function is generated from the software module offlineCalibration using the data generated in the previous step.
This module generates as output file a look-up table that contains an explicit representation of the undistortion function, used to correct the depth images, as described in the next step.
Notice that, from the training set obtained at Step 2, you can apply any other approximation algorithm and produce a look-up table in the same format.
– the easyDepthCalibrationStack provides two basic utilities, the calibration model learner and the calibration tool
– offlineCalibration
– computes the calibration model (as a look-up table) from the files generated by easydepthcalib
– It will produce a raw calibration matrix and an example KNN calibration matrix.
Use:
$./offlineCalibration <input_index_file> <calibration_model_file>
4. Correct the depth images with the undistortion look-up
The tool batchCalibration can be used to correct depth images applying the undistortion look-up table computed in the previous step.
$ ./batchCalibration -i <original_pgm_dir> -o <undistorted_pgm_dir> -c <calibration_model_file>
Is also possible to run the online driver. It will subscribe to a depth_image topic to produce an undistorted depth_image in real time.
5. Step five
There is no step five. You have done! The images produced in the step 4 are the corrected ones!