|
From: <hsu...@us...> - 2009-07-22 14:44:05
|
Revision: 19403
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19403&view=rev
Author: hsujohnhsu
Date: 2009-07-22 14:44:02 +0000 (Wed, 22 Jul 2009)
Log Message:
-----------
update head stereo hztests due to changes in pr2.xacro.xml to use wide_stereo and narrow_stereo.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/hztest_pr2_image.launch
pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml
Modified: pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/hztest_pr2_image.launch
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/hztest_pr2_image.launch 2009-07-22 09:07:13 UTC (rev 19402)
+++ pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/hztest_pr2_image.launch 2009-07-22 14:44:02 UTC (rev 19403)
@@ -13,18 +13,17 @@
<node pkg="pr2_mechanism_controllers" type="send_laser_traj_cmd_ms2.py" args="laser_tilt_controller" />
<!-- start stereo -->
- <include file="$(find stereo_image_proc)/stereoproc.launch" />
+ <include file="$(find stereo_image_proc)/wide_stereoproc.launch" />
+ <include file="$(find stereo_image_proc)/narrow_stereoproc.launch" />
<!-- Run hztest -->
<!-- Test for publication rate of 'stereo/cloud' topic -->
- <test test-name="hztest_test_stereo_cloud" pkg="rostest" type="hztest" time-limit="60" name="stereo_cloud_test">
+ <test test-name="hztest_test_narrow_stereo_cloud" pkg="rostest" type="hztest" time-limit="60" name="narrow_stereo_cloud_test">
<!-- The topic to listen for -->
- <param name="topic" value="/stereo/cloud" />
- <!-- The expected publication rate [Hz]. Set to 0.0 to only check that
- at least one message is received. -->
+ <param name="topic" value="/narrow_stereo/cloud" />
+ <!-- The expected publication rate [Hz]. Set to 0.0 to only check that at least one message is received. -->
<param name="hz" value="20.0" />
- <!-- Acceptable error in the publication rate [Hz]. Ignored if hz is set
- to 0.0. -->
+ <!-- Acceptable error in the publication rate [Hz]. Ignored if hz is set to 0.0. -->
<param name="hzerror" value="1.0" />
<!-- Time to listen for [seconds] -->
<param name="test_duration" value="2.0" />
@@ -36,33 +35,67 @@
<param name="check_intervals" value="false" />
</test>
- <!-- Test for publication of 'left stereo camera image publish rate' topic -->
- <test test-name="hztest_test_stereo_left_image" pkg="rostest" type="hztest" time-limit="60" name="stereo_left_image_test">
- <param name="topic" value="/stereo/left/image" />
+ <!-- Test for publication of 'left narrow_stereo camera image publish rate' topic -->
+ <test test-name="hztest_test_narrow_stereo_left_image" pkg="rostest" type="hztest" time-limit="60" name="narrow_stereo_left_image_test">
+ <param name="topic" value="/narrow_stereo/left/image" />
<param name="hz" value="20.0" />
<param name="hzerror" value="1.0" />
<param name="test_duration" value="2.0" />
<param name="check_intervals" value="false" />
</test>
- <!-- Test for publication of 'left stereo camera image publish rate' topic -->
- <test test-name="hztest_test_stereo_right_image" pkg="rostest" type="hztest" time-limit="60" name="stereo_right_image_test">
- <param name="topic" value="/stereo/right/image" />
+ <!-- Test for publication of 'right narrow_stereo camera image publish rate' topic -->
+ <test test-name="hztest_test_narrow_stereo_right_image" pkg="rostest" type="hztest" time-limit="60" name="narrow_stereo_right_image_test">
+ <param name="topic" value="/narrow_stereo/right/image" />
<param name="hz" value="20.0" />
<param name="hzerror" value="1.0" />
<param name="test_duration" value="2.0" />
<param name="check_intervals" value="false" />
</test>
- <!-- Test for publication of 'raw_stereo' topic. -->
- <test test-name="hztest_test_raw_stereo" pkg="rostest" type="hztest" time-limit="50" name="raw_stereo_test">
- <!-- Note how we use a different parameter namespace and node name
- for this test (raw_stereo_test vs. scan_test). -->
- <param name="topic" value="/stereo/raw_stereo" />
+ <!-- Test for publication of narrow 'raw_stereo' topic. -->
+ <test test-name="hztest_test_narrow_raw_stereo" pkg="rostest" type="hztest" time-limit="50" name="narrow_raw_stereo_test">
+ <param name="topic" value="/narrow_stereo/raw_stereo" />
<param name="hz" value="20.0" />
<param name="hzerror" value="1.0" />
<param name="test_duration" value="2.0" />
<param name="check_intervals" value="false" />
</test>
+ <!-- Run hztest -->
+ <test test-name="hztest_test_wide_stereo_cloud" pkg="rostest" type="hztest" time-limit="60" name="wide_stereo_cloud_test">
+ <param name="topic" value="/wide_stereo/cloud" />
+ <param name="hz" value="20.0" />
+ <param name="hzerror" value="1.0" />
+ <param name="test_duration" value="2.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+
+ <!-- Test for publication of 'left wide_stereo camera image publish rate' topic -->
+ <test test-name="hztest_test_wide_stereo_left_image" pkg="rostest" type="hztest" time-limit="60" name="wide_stereo_left_image_test">
+ <param name="topic" value="/wide_stereo/left/image" />
+ <param name="hz" value="20.0" />
+ <param name="hzerror" value="1.0" />
+ <param name="test_duration" value="2.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+
+ <!-- Test for publication of 'right wide_stereo camera image publish rate' topic -->
+ <test test-name="hztest_test_wide_stereo_right_image" pkg="rostest" type="hztest" time-limit="60" name="wide_stereo_right_image_test">
+ <param name="topic" value="/wide_stereo/right/image" />
+ <param name="hz" value="20.0" />
+ <param name="hzerror" value="1.0" />
+ <param name="test_duration" value="2.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+
+ <!-- Test for publication of wide 'raw_stereo' topic. -->
+ <test test-name="hztest_test_wide_raw_stereo" pkg="rostest" type="hztest" time-limit="50" name="wide_raw_stereo_test">
+ <param name="topic" value="/wide_stereo/raw_stereo" />
+ <param name="hz" value="20.0" />
+ <param name="hzerror" value="1.0" />
+ <param name="test_duration" value="2.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-22 09:07:13 UTC (rev 19402)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-22 14:44:02 UTC (rev 19403)
@@ -220,11 +220,11 @@
<!-- Wide camera is on robot right (hca1), narrow on left (hca2)? -->
<!-- 15mm offset from center needs check with CAD -->
- <stereo_camera parent="${name}_link" name="${name}_wide" >
+ <stereo_camera parent="${name}_link" name="wide_stereo" >
<origin xyz="0 -0.015 0" rpy="0 0 0" />
</stereo_camera>
- <stereo_camera parent="${name}_link" name="${name}_narrow" >
+ <stereo_camera parent="${name}_link" name="narrow_stereo" >
<origin xyz="0 0.015 0" rpy="0 0 0" />
</stereo_camera>
</macro>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|