1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26
|
<launch>
<arg name="gui" default="true" />
<node name="play_vslam_bag" pkg="rosbag" type="play" args="-l $(find opencv_apps)/test/vslam_tutorial.bag -s 5 --topics /narrow_stereo/left/image_rect" />
<group ns="narrow_stereo/left" >
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect" if="$(arg gui)" />
<!-- fback_flow.cpp -->
<include file="$(find opencv_apps)/launch/fback_flow.launch" >
<arg name="debug_view" value="$(arg gui)" />
<arg name="use_camera_info" value="false" />
<arg name="image" value="image_rect" />
</include>
<!-- Test Codes -->
<node name="fback_flow_saver" pkg="image_view" type="image_saver" args="image:=fback_flow/image" >
<param name="filename_format" value="$(find opencv_apps)/test/fback_flow.png"/>
</node>
<param name="fback_flow_test/topic" value="fback_flow/flows" /> <!-- opencv_apps/FlowArrayStamped -->
<test test-name="fback_flow_test" pkg="rostest" type="hztest" name="fback_flow_test" >
<param name="hz" value="15" />
<param name="hzerror" value="14" />
<param name="test_duration" value="5.0" />
</test>
</group>
</launch>
|