dji-sdk / Guidance-SDK-ROS

The official ROS package of Guidance SDK for 32/64 bit Ubuntu and XU3
80 stars 87 forks source link

Calibration #13

Closed sytelus closed 8 years ago

sytelus commented 8 years ago

In section "Using ROS tools for calibration and stereo processing", following should be modified,

roslaunch guidance load_calib_file.launch
(The launch file just sets a couple of parameters to retrieve the calibration files)

rosrun guidance guidanceNodeCalibration

rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 right:=/guidance/right/image_raw left:=/guidance/left/image_raw right_camera:=/guidance/right left_camera:=/guidance/left --no-service-check

as

To launch guidance node with calibration: roslaunch guidance load_calib_file.launch
(The launch file just sets a couple of parameters to retrieve the calibration files)

To use ROS calibration: rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 right:=/guidance/right/image_raw left:=/guidance/left/image_raw right_camera:=/guidance/right left_camera:=/guidance/left --no-service-check

Current commands asks to run the launch file followed by guidanceNodeCalibration. We can't run guidanceNodeCalibration without parameters so it will give following error:

terminate called after throwing an instance of 'YAML::TypedBadConversion<int>'
  what():  yaml-cpp: error at line 0, column 0: bad conversion
Aborted (core dumped)

If you run both launch file AND guidanceCalibrationNode then you will get error like this:

llibusb_get_device_list ret = 15 !!! 
open failed   001!
hdev NULL!  usb.cpp 351
usb write error!: Interrupted system call
Error happened!
Error: e_timeout at 350,/home/shitals/vso/msresearch/Theseus/catkin_ws/src/Guidance-SDK-ROS/src/GuidanceNodeCalibration.cpp
release usb,usb.cpp 301

Another clarification required in documentation is how to move calibration parameters from terminal to YAML. Currently guidanceNodeCalibration prints:

Sensor online status: 1 1 1 1 1 
cu  cv  focal   baseline
166.582 123.588 282.914 0.150614
158.709 117.412 252.387 0.149986
161.201 116.399 243.976 0.150173
157.178 116.089 258.334 0.150176
160.889 117.302 258.253 0.151675

It looks to me this will only affect camera matrix in YAML which is Hartley and Zisserman (see http://ksimek.github.io/2013/08/13/intrinsic/),

jgoppert commented 8 years ago

@sytelus See this patch for fixing the calibration program: https://github.com/dji-sdk/Guidance-SDK-ROS/pull/11/commits/dc5f6bd861133c6b48d8b72d0bb41e6a8c8f7f2d

With this I can run calibration without getting errors and get the same table you are showing.

As far as I can tell it only reads the parameters. Is there a way to set the stereo calibration? When I try to run the calibration in Windows 10 I get an error.