stereo_proc NO subscription so NO stereo_images
Hi everybody
I was wondering if someone has ever seen something like that.
I'm using two uEye USB camera with a personnal arduino trigger. Everything works fine. The calibration setup is OK. But when I try to launch the stereo_proc node, I can clearly see with rxgraph (or rosnode info) that stereo/proc as no subscriptions. And according to the stereo_image_proc tutorial I should have
Subscriptions:
- /stereo/left/image_raw [sensor_msgs/Image]
/stereo/left/camera_info [sensor_msgs/CameraInfo]
/stereo/right/image_raw [sensor_msgs/Image]
- /stereo/right/camera_info [sensor_msgs/CameraInfo]
And I'm thinking that's why I can not go further with the my stereo bench.
Here is my launch file.
<launch>
<!-- first camera and associated image pipeline -->
<group ns="stereo_test" >
<!-- left camera -->
<node pkg="cameraUEYE" type="cameraUEYE_node" name="cameraUEYE_left_node" >
<param name="guid" value="1" />
<param name="frame_id" value="cam_left" />
<param name="use_ros_time" value="true" />
<param name="use_external_trigger" value="true" />
<param name="frame_rate" value="50" />
<param name="camera_info_url" value="file:///home/vvittori/.ros/camera_info/UEYE_USB_1.yaml"/>
<remap from="camera" to="left" />
</node>
<!-- right camera -->
<node pkg="cameraUEYE" type="cameraUEYE_node" name="cameraUEYE_right_node" >
<param name="guid" value="2" />
<param name="frame_id" value="cam_right" />
<param name="use_ros_time" value="true" />
<param name="use_external_trigger" value="true" />
<param name="frame_rate" value="50" />
<param name="camera_info_url" value="file:///home/vvittori/.ros/camera_info/UEYE_USB_2.yaml"/>
<remap from="camera" to="right" />
</node>
<!-- STEREO IMAGE PROC -->
<node pkg="stereo_image_proc" type="stereo_image_proc" respawn="false" name="proc" args="_approximate_sync:=True" />
</group>
<!-- monitoring and configuration tools -->
<node pkg="rxtools" type="rxconsole" name="rxconsole" />
<node pkg="dynamic_reconfigure" type="reconfigure_gui"
name="reconfigure_gui" />
</launch>
Any hints are welcomed !
Thanks
Regards
EDIT :
Thanks to Patrick I was able to understand that part in the wiki page ! (Cf. Patrick answer)
I was still block at the rosnode info stereo/proc
results that they give us.
Anyway I've tried what he told me with the following command line (I have change stereo_test to stereo in my launch file)
ROS_NAMESPACE=stereo rosrun stereo_image_proc stereo_image_proc __name:=PROC
and
rosrun image_view stereo_view stereo:=/stereo image:=image_rect
as written in the wiki page. Then, I did see what you told me that right after I launch the previous command it subscribed at
[ INFO] [1334565947.793592670]: Subscribing to:
* /stereo/left/image_rect
* /stereo/right/image_rect
* /stereo/disparity
and yet I had the following error that occured :
OpenCV Error: Assertion failed (0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows) in Mat, file /tmp/buildd/libopencv-2.3.1+svn6514+branch23/modules/core/src/matrix.cpp, line 303
OpenCV Error: Assertion failed (0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows) in Mat, file /tmp/buildd/libopencv-2.3.1+svn6514+branch23/modules/core/src/matrix.cpp, line 303
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/buildd/libopencv-2.3.1+svn6514+branch23/modules/core/src/matrix.cpp:303: error: (-215) 0 <= roi.x && 0 <= roi ...
Shouldn't the <group> namespace be
stereo
and notstereo_test
?It was a "test" choice but I think that it is not a big deal as long as you specified it in the ROS_NAMESPACE . I maybe wrong I'll check it !
Are your camera_info and image sizes set properly? Could you include a short bagfile with your cameras streaming images and infos that reproduces that OpenCV assertion?
I don't know what properly set is for you ? Here is in the main post the bag file you ask . Thank you