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

Revision history [back]

Try swapping your remaps in stereo_image_proc so that they read:

<remap from="left/image_raw" to="left/image"/>
<remap from="right/image_raw" to="right/image"/>

When you remap topics for a node you are remapping from what is _expected_ by the node to what you are _providing_. The stereo_image_proc node _expects_ to receive image_raw, but you are _providing_ image. That should get rid of the warnings that are printed by stereo_image_proc about input topics not being advertised yet.

Once stereo_image_proc has the correct input topics then it will start to publish rectified images, a disparity image, and a point cloud. That should also fix your issue with image_view/stereo_view.

Try swapping your remaps in stereo_image_proc so that they read:

<remap from="left/image_raw" to="left/image"/>
<remap from="right/image_raw" to="right/image"/>

When you remap topics for a node you are remapping from what is _expected_ by the node to what you are _providing_. The stereo_image_proc node _expects_ to receive image_raw, but you are _providing_ image. That should get rid of the warnings that are printed by stereo_image_proc about input topics not being advertised yet.

Once stereo_image_proc has the correct input topics then it will start to publish rectified images, a disparity image, and a point cloud. You will need to swap the remaps in image_view/stereo_view as well. That should also fix your issue with image_view/stereo_view.

Try swapping your remaps in stereo_image_proc so that they read:

<remap from="left/image_raw" to="left/image"/>
<remap from="right/image_raw" to="right/image"/>

When you remap topics for a node you are remapping from what is _expected_ by the node to what you are _providing_. The stereo_image_proc node _expects_ to receive image_raw, but you are _providing_ image. That should get rid of the warnings that are printed by stereo_image_proc about input topics not being advertised yet.

Once stereo_image_proc has the correct input topics then it will start to publish rectified images, a disparity image, and a point cloud. You will need to swap the remaps first remap in image_view/stereo_view as well. That should also fix your issue with image_view/stereo_view.

Try swapping your remaps in stereo_image_proc so that they read:

<remap from="left/image_raw" to="left/image"/>
<remap from="right/image_raw" to="right/image"/>

When you remap topics for a node you are remapping from what is _expected_ by the node to what you are _providing_. The stereo_image_proc node _expects_ to receive image_raw, but you are _providing_ image. That should get rid of the warnings that are printed by stereo_image_proc about input topics not being advertised yet.

Once stereo_image_proc has the correct input topics then it will start to publish rectified images, a disparity image, and a point cloud. You will need to swap the first remap in image_view/stereo_view as well. That should also fix your issue with image_view/stereo_view.

EDIT (for new question): Take a look at the stereo_image_proc parameters. The stereo_image_proc node assumes all input messages are exactly synchronized with respect to the timestamps in their headers. Inside the node tags add:

<param name="approximate_sync" value="true"/>
<param name="queue_size" value="10"/>

This will help if you do not have hardware triggering/syncing of your image_raw and camera_info topics.