Jack, thanks for taking a look into this. I would agree with you that everything at the driver level (/image_raw, /camera_info and /set_camera_info) seems to be okay, since those topics are broadcasting and all. Here are the contents of the calibration_left.yaml file: image_width: 640 image_height: 480 camera_name: left camera_matrix: rows: 3 cols: 3 data: [3393.8, 0, 286.397, 0, 3381.29, 290.204, 0, 0, 1] distortion_coefficients: rows: 1 cols: 5 data: [0.0767399, -45.545, -0.00829002, -0.00495522, 0] rectification_matrix: rows: 3 cols: 3 data: [1, 0, 0, 0, 1, 0, 0, 0, 1] projection_matrix: rows: 3 cols: 4 data: [3393.8, 0, 286.397, 0, 0, 3381.29, 290.204, 0, 0, 0, 1, 0] Here is an output of the camera_info topic when my launch file is running: header: seq: 149 stamp: 0 frame_id: /left height: 480 width: 640 roi: x_offset: 0 y_offset: 0 height: 0 width: 0 D: [0.0767399, -45.545000000000002, -0.0082900200000000004, -0.0049552199999999998, 0.0] K: [3393.8000000000002, 0.0, 286.39699999999999, 0.0, 3381.29, 290.20400000000001, 0.0, 0.0, 1.0] R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] P: [3393.8000000000002, 0.0, 286.39699999999999, 0.0, 0.0, 3381.29, 290.20400000000001, 0.0, 0.0, 0.0, 1.0, 0.0] So, those seem to agree so I would think it is parsing the yaml file okay. I'm just starting to play with vision and these cameras, so I can't really say what a "sensible" calibration would be beyond, yes, it seems to have all the values that the camera_info topic is publishing and cameracalibrator.py's calibrate button was greenish when I did the calibration, as per the tutorial. When I was calibrating, I did not have the camera_info_manager/url set, so I let it save to /temp/calibration_left.yaml, copied that to my package and then told the camera1394 node where to find it. If it matters at all, the camera is a Point Grey FL2-03S2C connected with a 9-pin to 6-pin firewire cable to the Ubuntu 9.10 laptop. If you aren't able to reproduce it with a test of your own, I made a bag file with just the camera1394 node running with the same parameters as in the launch file. You can find it here: http://mobilerobots.case.edu/files/image_proc_test_2010-03-25-20-55-27.bag.tar.gz . The only problem is that it is kinda big (~300 MB), since I'm not using a compressed image_transport or anything yet. The bag exhibited the same image_proc problem as I described earlier when running off the live camera. Thanks Eric Perko wisesage5001@gmail.com eric.perko@case.edu mobilerobots.case.edu On Thu, Mar 25, 2010 at 8:21 PM, Jack O'Quin wrote: > On Thu, Mar 25, 2010 at 6:35 PM, Eric Perko wrote: >> Hi all, >> >> I'm currently trying to use the ROS image_pipeline and the new >> camera1394 driver to get some Point Grey 1394 cameras up and running. >> For some reason, I am unable to view any of the topic being published >> by image_proc. First, here is the launch file I am using to start up >> the camera and image_proc: >> >> >> >> >> >> > value="file:///home/eric/code/cwrucam/cwrucam/calibration/calibration_left.yaml" >> /> >> >> >> >> >> After running this, I get the following output from rostopic list -v: >> >> Published topics: >>  * /left/camera/image_rect_color [sensor_msgs/Image] 1 publisher >>  * /left/camera/image_rect [sensor_msgs/Image] 1 publisher >>  * /left/camera/camera_info [sensor_msgs/CameraInfo] 1 publisher >>  * /rosout [roslib/Log] 2 publishers >>  * /left/camera/image_raw [sensor_msgs/Image] 1 publisher >>  * /rosout_agg [roslib/Log] 1 publisher >>  * /left/camera/image_color [sensor_msgs/Image] 1 publisher >>  * /left/camera/image_mono [sensor_msgs/Image] 1 publisher >> >> Subscribed topics: >>  * /clock [unknown type] 3 subscribers >>  * /rosout [roslib/Log] 1 subscriber >> >> So, based on that, I can see that the image_proc node is actually up >> and running. I am able to do "rosrun image_view image_view >> image:=/left/camera/image_raw" and see the color image from my camera >> streaming in. rostopic hz also confirms that both >> /left/camera/image_raw and /left/camera/camera_info are running at >> about 15 fps. >> >> Now, when I run "rosrun image_view image_view >> image:=/left/camera/image_rect_color" (or any other image_proc >> published topic), I get a blank window with no image in it. Running >> rostopic list -v again while the image_view node is running gives me >> the following: >> >> Published topics: >>  * /left/camera/image_rect_color [sensor_msgs/Image] 1 publisher >>  * /left/camera/image_rect [sensor_msgs/Image] 1 publisher >>  * /left/camera/camera_info [sensor_msgs/CameraInfo] 1 publisher >>  * /rosout [roslib/Log] 3 publishers >>  * /left/camera/image_raw [sensor_msgs/Image] 1 publisher >>  * /rosout_agg [roslib/Log] 1 publisher >>  * /left/camera/image_color [sensor_msgs/Image] 1 publisher >>  * /left/camera/image_mono [sensor_msgs/Image] 1 publisher >> >> Subscribed topics: >>  * /left/camera/image_rect_color [sensor_msgs/Image] 1 subscriber >>  * /clock [unknown type] 4 subscribers >>  * /left/camera/camera_info [sensor_msgs/CameraInfo] 1 subscriber >>  * /rosout [roslib/Log] 1 subscriber >>  * /left/camera/image_raw [sensor_msgs/Image] 1 subscriber >> >> So, I can see that image_proc is subscribing to the correct topics and >> image_view is also on the correct topic. I also tried starting the >> image_proc node from the command line as indicated at >> http://www.ros.org/wiki/image_proc but got the exact same behavior as >> with the launch file. In either case, rostopic hz >> /left/camera/image_rect_color just outputs that it is subscribing to >> the topic and waits. >> >> I'm pretty sure the camera is properly calibrated, as I just finished >> calibrating it using the directions at >> http://www.ros.org/wiki/camera_calibration/Tutorials/MonocularCalibration >> and it worked fine and output a .yaml file when I hit upload in the >> calibration GUI. rostopic echo on the /left/camera/camera_info topic >> gives me the values that are in the calibration file. I'm assuming >> that even if the calibration were somehow off, I should still at least >> see the image_pipeline attempting to display an image_rect_color >> topic. >> >> So, I'm a bit stumped as to what to do to narrow down what is causing >> this behavior, since I get no error output in any of my terminal >> windows. I'm running the latest based on these .rosinstall files: >> http://ros.org/rosinstalls/latest_pr2.rosinstall with >> http://www.ros.org/rosinstalls/wg_latest_devel.rosinstall in an >> overlay. >> >> Are there some steps I can take to try to debug this problem? Has >> anyone else experienced this type of issue with the new camera1394 >> driver? > > Thanks for the report, Eric. > > You seem to be farther along than I have gotten with this driver. From > your report, it looks like the things I tested so far are working > (image_raw, camera_info, set_camera_info), and your driver setup looks > right to me. > > I have not yet tried to run a rectified image with it. Maybe the > driver is not producing exactly what image_proc expects. Perhaps the > ROS experts can help us. > > Did the calibration data look sensible? What was saved in this file? > >  /home/eric/code/cwrucam/cwrucam/calibration/calibration_left.yaml > > There are still some known problems with saving the calibration data > initially. The YAML parser does not tolerate missing or empty files > very well. So, if the calibration looks wrong, try waiting to set the > camera_info_manager/url parameter until after the driver has started > and before running the calibration. Then, it should start up with no > calibration, but still store the data where you want them. > > I'll try to duplicate your test and let you know what (if anything) I > discover. I probably won't get to it tonight, however. > > Regards, > -- >  joq > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users >