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

How do you configure uvc_camera?

asked 2011-04-20 12:12:25 -0500

rbtying gravatar image

updated 2011-04-21 07:55:33 -0500

I'm trying to get my camera_node working, and it doesn't seem to be taking the parameters given into account at all.

My launch file (excerpt):

    
  <group ns="lifecam">
    <node name="lifecam" pkg="uvc_camera" type="camera_node" output="screen">
           
    </node>
  </group>

Output from rostopic echo /lifecam/camera_info

header: 
  seq: 463
  stamp: 
    secs: 1303400952
    nsecs: 715715842
  frame_id: camera
height: 480
width: 640
distortion_model: ''
D: []
K: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
R: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
P: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
binning_x: 0
binning_y: 0
roi: 
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False
---

Clearly the calibration data is not being read (thus a bunch of zeros in the camera_info message), and the width/height parameters are the defaults, not the values I set them to.

I'm not sure what I'm doing wrong here: I can view the image stream in rviz, but rviz will complain about NaNs and infs in the calibration data (since it's not being read). Help would be greatly appreciated.

lifecam.yaml

$ cat rover/lifecam.yaml 
---
image_width: 640
image_height: 480
camera_name: camera
camera_matrix:
  rows: 3
  cols: 3
  data: [661.285, 0, 391.756, 0, 650.523, 205.652, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [0.125743, 0.237875, -0.0083126, 0.0506531, 0]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
  rows: 3
  cols: 4
  data: [661.285, 0, 391.756, 0, 0, 650.523, 205.652, 0, 0, 0, 1, 0]

I just updated the above data as per Markus Bader's recommendations - doesn't seem to have worked. The camera was recalibrated, and it appears that it is certainly not reading the params set: when set_camera_info is called, it saves the data into /tmp/calibration.yaml, not the file set in the launchfile. Thanks for all the help!

-- EDIT -- This seems to be some sort of a weird rosparam problem - I just tried to set the parameters by editing the defaults in /opt/ros/diamondback/stacks/camera_umd/uvc_camera/src/camera.cpp, and calibration data and everything work from there.

edit retag flag offensive close merge delete

Comments

What does your lifecam.ini file look like? Did you calibrate using the camera_calibration package and "commit" the calibration to that file?
Eric Perko gravatar image Eric Perko  ( 2011-04-20 13:39:49 -0500 )edit
Yes, I did - see above for the lifecam.ini
rbtying gravatar image rbtying  ( 2011-04-20 14:38:06 -0500 )edit
The combination of nodelets and the explicit node name is triggering the problem. With e.g.: "ROS_NAMESPACE=camera rosrun uvc_camera camera_node _width:=800 _height:=600 __name:=lifecam" the /camera/lifecam/height param is set but getPrivateNode still has us looking at /camera/uvc_camera/height
Ken gravatar image Ken  ( 2011-04-21 14:05:34 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
1

answered 2011-04-20 14:53:00 -0500

Eric Perko gravatar image

It looks like you are setting the size of the image to something different than what you calibrated with. The lifecam.ini is calibrated for 640x480, but you have the camera configured for 320x240. The camera calibration size needs to match the size of the image; the camera_info_manager doesn't handle the current image size being different than the calibrated size if I recall correctly.

Try setting the camera to 640x480 and see if the problem still occurs. If not, try setting the resolution to 320x240 and then recalibrating and using the new file. A shortcut could be to just edit your calibration's width and height values, but there is no guarantee that the calibration will still be correct at the different image size.

edit flag offensive delete link more

Comments

I tried setting width/height to 640x480, as well as changing the ini file's parameters, but there's no change: the camera_info still says 640x480 (regardless of what I set height/width to in both the launch and ini files), and the other values are all zero.
rbtying gravatar image rbtying  ( 2011-04-20 14:59:41 -0500 )edit
It's probably worth noting that it did accept the calibration from the cameracalibrator.py's 'commit', it just didn't keep it after the instance was killed | also that NONE of the params are being set - changing the frame doesn't work, nor the dimensions, nor the framerate.
rbtying gravatar image rbtying  ( 2011-04-20 15:01:10 -0500 )edit
1

answered 2011-04-21 01:15:58 -0500

Markus Bader gravatar image

Hi

I see there also an other problem in your launch file. You should not use absolute paths like you did in accept you realy want that :-)

<remap from="/image_raw" to="/lifecam/image_raw"/>
<remap from="/camera_info" to="/lifecam/camera_info"/>
<remap from="/set_camera_info" to="/lifecam/set_camera_info"/>

Better is to go with a name space or without the starting slashes.

<launch> 
  <group ns="lifecam" >
    <node name="lifecam" pkg="uvc_camera" type="camera_node">
      <param name="device" type="string" value="/dev/video0"/>
      <param name="width" type="int" value="320"/>
      <param name="height" type="int" value="240"/>
      <param name="fps" type="int" value="10"/>
    </node>
  </group>
</launch>
edit flag offensive delete link more
0

answered 2011-04-21 01:35:53 -0500

Markus Bader gravatar image

updated 2011-04-21 01:40:45 -0500

Hi

Back to your original question. The ros camera calibration delivers you a *.ini file, but that's not usable for the uvc_camera driver you should convert that to a *.yml file. Have a look at the camera_calibration_parsers --> http://www.ros.org/wiki/camera_calibration_parsers I made a link on the http://www.ros.org/wiki/camera_calibration/Tutorials/MonocularCalibration --> on the bottom so its easier to find how to do.

<launch>  
  <group ns="lifecam" >
     <node name="lifecam" pkg="uvc_camera" type="camera_node">
     <param name="camera_info_url" value="file://$(find YOUR_NOTENAME)/cal.yml" />
     <param name="device" type="string" value="/dev/video0"/>
     <param name="width" type="int" value="320"/>
     <param name="height" type="int" value="240"/>
     <param name="fps" type="int" value="10"/>
  </node>
 </group> 
</launch>

The cal.yml file:

image_width: 640
image_height: 480
camera_name: lifecam
camera_matrix:
  rows: 3
  cols: 3
  data: [522.284, 0, 294.957, 0, 519.92, 221.282, 0, 0, 1]
distortion_coefficients:
  rows: 1
  cols: 5
  data: [0.075017, -0.17182, -0.005117, -0.00046, 0]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
  rows: 3
  cols: 4
  data: [522.284, 0, 294.957, 0, 0, 519.92, 221.282, 0, 0, 0, 1, 0]
edit flag offensive delete link more

Comments

Thanks! I edited my question above to show the newer data - while your suggestions definitely make sense, they don't appear to have solved the problem. Are there any other debug files I should be looking at?
rbtying gravatar image rbtying  ( 2011-04-21 03:53:04 -0500 )edit

Question Tools

Stats

Asked: 2011-04-20 12:12:25 -0500

Seen: 4,895 times

Last updated: Apr 21 '11