ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
4

How to get and use camera calibration file?

asked 2011-12-06 04:41:25 -0500

Thomas D gravatar image

updated 2011-12-06 09:22:31 -0500

I am running on Lucid 32-bit from Electric debs. I have been able to run the mono calibration utility with a 1394 camera and get a successful calibration. How do I then get the actual camera calibration file that was saved to disk and use it in a launch file to get rectified images?

Steps To Reproduce:

Start camera1394 and cameracalibration with the following launch file:

<launch>
  <group ns="stereo">
    <node pkg="camera1394" type="camera1394_node" name="camera_left">
      <rosparam file="$(find stereo_calibration)/cameras/left_flea2.yaml"/>
      <remap from="camera" to="left"/>
    </node>
  </group>

  <node pkg="camera_calibration" type="cameracalibrator.py" name="mono_calibration"
    args="-size 9x6 -square 0.054 image:=/stereo/left/image_raw camera:=/stereo/left">
  </node>
</launch>

and the following yaml file:

# ID number of camera. Use Coriander to find it.
guid: xxxxxxxxxxxxxxxx
# Mode describes the size and number of channels for the images.
video_mode: 1600x1200_mono8
# The frame_id MUST be part of your URDF to display stereo data correctly in Rviz.
frame_id: left_camera
# The location of the ROS calibration file.
camera_info_url: package://stereo_calibration/cameras/xxxxxxxxxxxxxxxx_mono.yaml
# Frames per second.
frame_rate: 30
# Try to reset the camera when opening.
reset_on_open: true
# Change from default 400Mbps Firewire.
iso_speed: 800

So far so good, as I get the utility to show up, all the bars go green, I can click 'Save' and 'Commit', and then exit out of the launch file.

There is a file created at /tmp/calibrationdata.tar.gz that I am able to open and see 74 images plus a file named ost.txt. Using the converter utility I am able to get a yaml file with the following contents:

image_width: 1600
image_height: 1200
camera_name: narrow_stereo/left
camera_matrix:
  rows: 3
  cols: 3
  data: [2379.692159, 0, 810.664016, 0, 2364.724193, 565.047935, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [-0.125793, 0.149249, -0.000565, -0.000972, 0]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
  rows: 3
  cols: 4
  data: [2348.257291, 0, 809.568039, 0, 0, 2344.569053, 563.818346, 0, 0, 0, 1, 0]

I modified the camera_name field to be stereo/left but it made no difference in the errors described below.

Errors: The output of running a launch file similar to above but with image_proc and two image viewers is:

[ERROR] [1323196102.210752328]: Unable to open camera calibration file [~/.ros/camera_info/camera.yaml]
[ERROR] [1323196102.427796451]: Unable to open camera calibration file [~/.ros/camera_info/00b09d0100a8f71b.yaml]
... logging to x.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://localhost:58044/

SUMMARY
========

PARAMETERS
 * /stereo/camera_left/frame_id
 * /rosdistro
 * /stereo/camera_left/frame_rate
 * /stereo/camera_left/camera_info_url
 * /stereo/camera_left/iso_speed
 * /stereo/camera_left/guid
 * /rosversion
 * /stereo/camera_left/reset_on_open
 * /stereo/camera_left/video_mode

NODES
  /stereo/left/
    left_image_proc (image_proc/image_proc)
  /stereo/
    camera_left (camera1394/camera1394_node)
    left_raw (image_view/image_view)
    left_rect (image_view/image_view)

auto-starting new master
process[master]: started with pid [30321]
ROS_MASTER_URI=http://localhost:11311
~/stereo_calibration/stereo_calibration ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
5

answered 2011-12-06 07:19:30 -0500

joq gravatar image

updated 2017-09-09 03:12:24 -0500

130s gravatar image

What you are doing looks mostly OK. The error messages you got are misleading and irrelevant. There is an enhancement ticket to fix them in Fuerte.

To answer your specific questions:

  1. I think so. Clicking the "COMMIT" button on the calibration menu should store the new calibration data at the specified URL, which need not have existed before then, although the package directory should already exist.

  2. No.

  3. Yes. Electric has a new feature, allowing you to substitute the camera name (GUID) as part of the URL, like package://stereo_calibration/cameras/${NAME}.yaml. For your device, that would resolve to package://stereo_calibration/cameras/00b09d0100a8f71b.yaml (reference to api doc)

  4. Maybe not, depending on how good your lenses are.

The camera_name in the saved calibration file should be 00b09d0100a8f71b for your device. It should get set automatically. If the calibrated name does not agree with the actual device GUID, a warning will be logged.

edit flag offensive delete link more

Comments

I hope you don't mind my edit. I adjusted the original question with numbers; did the same here to match.
Asomerville gravatar image Asomerville  ( 2011-12-06 09:26:38 -0500 )edit
Good idea. Thanks.
joq gravatar image joq  ( 2011-12-06 09:43:42 -0500 )edit
I like it better. I tried to do it originally, but the formatting wouldn't work out as it always wanted to indent the numbers by ~2 spaces, i.e., 1 looked correct, 2 was 2 spaces to the right of 1, 3 was 2 spaces to the right of 2... Thanks.
Thomas D gravatar image Thomas D  ( 2011-12-06 09:59:05 -0500 )edit

In case of other camera drivers like the usb_cam is it the same? How can I find out the camera_name?

ZoltanS gravatar image ZoltanS  ( 2013-05-15 23:36:54 -0500 )edit

Many camera drivers use camera_info_manager and therefore behave similarly. The usb_cam driver apparently does not, so I don't know how it handles calibration and camera naming.

joq gravatar image joq  ( 2013-05-16 03:50:40 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-12-06 04:41:25 -0500

Seen: 27,067 times

Last updated: Sep 09 '17