Skip to content

Commit

Permalink
test multiple nodelet manager support (ros-drivers#108)
Browse files Browse the repository at this point in the history
  • Loading branch information
jack-oquin committed Oct 9, 2016
1 parent 4d0d71f commit ed6e94b
Show file tree
Hide file tree
Showing 2 changed files with 49 additions and 3 deletions.
4 changes: 1 addition & 3 deletions velodyne_pointcloud/tests/CMakeLists.txt
Expand Up @@ -44,11 +44,9 @@ add_rostest(cloud_node_64e_s2.1_hz.test)
add_rostest(cloud_nodelet_64e_s2.1_hz.test)
add_rostest(cloud_node_vlp16_hz.test)
add_rostest(cloud_nodelet_vlp16_hz.test)

## These tests don't work well enough to be worth the effort of
## running them:
add_rostest(transform_node_hz.test)
add_rostest(transform_nodelet_hz.test)
add_rostest(two_nodelet_managers.test)

# parse check all the launch/*.launch files
roslaunch_add_file_check(../launch)
48 changes: 48 additions & 0 deletions velodyne_pointcloud/tests/two_nodelet_managers.test
@@ -0,0 +1,48 @@
<!-- -*- mode: XML -*- -->
<!-- rostest of publishing using two different nodelet managers. -->

<launch>

<!-- use separate namespaces for each device and its nodelet manager -->

<group ns="hdl32e">

<!-- start nodelet manager, driver and cloud nodelets -->
<include file="$(find velodyne_pointcloud)/launch/32e_points.launch">
<arg name="frame_id" value="hdl32e"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/32e.pcap"/>
</include>

<!-- verify PointCloud2 publication rate -->
<test test-name="multi_nodelet_32e_test" pkg="rostest"
type="hztest" name="hztest_multi_nodelet_32e" >
<param name="hz" value="10.0" />
<param name="hzerror" value="3.0" />
<param name="test_duration" value="5.0" />
<param name="topic" value="/hdl32e/velodyne_points" />
<param name="wait_time" value="2.0" />
</test>

</group>

<group ns="vlp16">

<!-- start nodelet manager, driver and cloud nodelets -->
<include file="$(find velodyne_pointcloud)/launch/VLP16_points.launch">
<arg name="frame_id" value="vlp16"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/vlp16.pcap"/>
</include>

<!-- verify PointCloud2 publication rate -->
<test test-name="multi_nodelet_vlp16_test" pkg="rostest"
type="hztest" name="hztest_multi_nodelet_vlp16" >
<param name="hz" value="10.0" />
<param name="hzerror" value="3.0" />
<param name="test_duration" value="5.0" />
<param name="topic" value="/vlp16/velodyne_points" />
<param name="wait_time" value="2.0" />
</test>

</group>

</launch>

0 comments on commit ed6e94b

Please sign in to comment.