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

Stereo cameras no disparity output

asked 2016-04-24 13:06:48 -0500

chilypepper gravatar image

Hello,

I'm running 2 Point Grey Blackfly cameras in stereo and trying to get a disparity map out of them. I'm running into a ton of issues with getting to that point.

I fire up the cameras with the following launch file:

<launch>

<arg name="camera_serial" default="0"/> <arg name="calibrated" default="0"/>

<group ns="stereo">

<group ns="right" >
        <node pkg="nodelet" type="nodelet" name="manager" args="manager" />

    <node pkg="nodelet" type="nodelet" name="camera_nodelet" args="load pointgrey_camera_driver/PointGreyCameraNodelet manager">
        <param name="frame_id" value="right_camera"/>
        <param name="serial" value="14432788"/>
        <param name="camera_info_url" if="$(arg calibrated)"
        value="file://$(env HOME)/.ros/camera_info/14432788.yaml" />
        <param name="frame_rate" value="15"/>
    </node>
    <node name="image_proc_right" pkg="image_proc" type="image_proc"/>

</group>
<group ns="left" >
<node pkg="nodelet" type="nodelet" name="manager" args="manager" />

    <node pkg="nodelet" type="nodelet" name="camera_nodelet" args="load pointgrey_camera_driver/PointGreyCameraNodelet manager">
        <param name="frame_id" value="left_camera"/>
        <param name="serial" value="14490573"/>
        <param name="camera_info_url" if="$(arg calibrated)"
    value="file://$(env HOME)/.ros/camera_info/14432788.yaml" />
        <param name="frame_rate" value="15"/>
    </node>
    <node name="image_proc_left" pkg="image_proc" type="image_proc"/>
</group>

</group> </launch>

And then I run the calibration:

$ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.073 right:=/stereo/right/image_raw left:=/stereo/left/image_raw right_camera:=/stereo/right left_camera:=/stereo/left --approximate=0.01

This works all fine and dandy and I calibrate the pair with my board (24x31in, 9x7 squares, 8x6 interior corners). I achieved an epi of about .15-.2.

At this point, I commit the calibration, and run

$ ROS_NAMESPACE=/stereo rosrun stereo_image_proc stereo_image_proc

And here is where everything goes south. I run stereo_view or disparity view and nothing but blank windows. Stereo_view gets all of the regular images (image_rect, .._rect_color, etc.) but exactly 0 disparity images. I've tried changing parameters to no avail; I even made a program to run through random parameter values and left it going on the computer. After about 500,000 frames, all with different parameter values, and not a single disparity image output, I quit it.

I'm not sure where to go from here, the calibration is totally fine, but no matter what I do, I cannot get a disparity image out of stereo_image_proc. stereo_image_proc works just fine as I can get all of the rectified images out of it, so theres no connection issue, its just the disparity images that will not come out of it no matter what.

If anyone has any pointers, please let me know, this is becoming very stressful.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-04-25 01:02:34 -0500

JuliusGel gravatar image

updated 2016-04-25 01:07:37 -0500

The problem is camera sync. Your cameras are not synchronized and the processor never receives two images that would have the same time stamp and therefore never start processing images. By default stereo_image_proc uses exact sync strategy. This can by changed by modifying the stereo_image_proc.launch file.

The default file has this:

  <node pkg="nodelet" type="nodelet" name="disparity"
    args="load stereo_image_proc/disparity $(arg manager) $(arg bond)"
    respawn="$(arg respawn)" />

This should be changed to:

  <node pkg="nodelet" type="nodelet" name="disparity"
    args="load stereo_image_proc/disparity $(arg manager) $(arg bond)"
    respawn="$(arg respawn)">
     <param name="approximate_sync" value="True" />
  </node>

This will make sure that the two images are processed as soon as they are received.

edit flag offensive delete link more

Comments

I've been trying to solve this for weeks, turns out one little command line argument was the key. Thank you so much.

chilypepper gravatar image chilypepper  ( 2016-04-25 23:45:23 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-04-24 13:06:48 -0500

Seen: 1,212 times

Last updated: Apr 25 '16