Skip to content

Commit

Permalink
use new catkin_download_test_data() command
Browse files Browse the repository at this point in the history
  • Loading branch information
jack-oquin committed Jun 14, 2013
1 parent 531b1ff commit ac1f34b
Show file tree
Hide file tree
Showing 12 changed files with 32 additions and 42 deletions.
25 changes: 11 additions & 14 deletions velodyne_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,20 +33,17 @@ install(DIRECTORY include/${PROJECT_NAME}/
### TODO install some launch scripts and parameter files

# Download packet capture (PCAP) files containing test data.
#
# This appalling hack is to work around download_test_data(), which
# insists on copying files to the build tree, where rostest cannot
# find them.
set(SAVE_PROJECT_BINARY_DIR ${PROJECT_BINARY_DIR})
set(PROJECT_BINARY_DIR /tmp/${PROJECT_NAME})
download_test_data(http://pr.willowgarage.com/data/velodyne/class.pcap
tests/class.pcap
65808d25772101358a3719b451b3d015)

download_test_data(http://pr.willowgarage.com/data/velodyne/32e.pcap
tests/32e.pcap
e41d02aac34f0967c03a5597e1d554a9)
set(PROJECT_BINARY_DIR ${SAVE_PROJECT_BINARY_DIR})
# Store them in devel-space, so rostest can easily find them.
catkin_download_test_data(
${PROJECT_NAME}_tests_class.pcap
http://pr.willowgarage.com/data/velodyne/class.pcap
DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/tests
MD5 65808d25772101358a3719b451b3d015)
catkin_download_test_data(
${PROJECT_NAME}_tests_32e.pcap
http://pr.willowgarage.com/data/velodyne/32e.pcap
DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/tests
MD5 e41d02aac34f0967c03a5597e1d554a9)

# unit tests
add_rostest(tests/pcap_node_hertz.test)
Expand Down
2 changes: 1 addition & 1 deletion velodyne_driver/tests/pcap_32e_node_hertz.test
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<!-- start read with example PCAP file -->
<node pkg="velodyne_driver" type="velodyne_node" name="velodyne_node">
<param name="model" value="32E"/>
<param name="pcap" value="/tmp/velodyne_driver/tests/32e.pcap"/>
<param name="pcap" value="$(find velodyne_driver)/tests/32e.pcap"/>
</node>

<test test-name="pcap_hertz_test" pkg="rostest" type="hztest" name="hztest1" >
Expand Down
3 changes: 1 addition & 2 deletions velodyne_driver/tests/pcap_32e_nodelet_hertz.test
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@
<!-- start nodelet manager, driver and pointcloud nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="model" value="32E"/>
<arg name="pcap"
value="/tmp/velodyne_driver/tests/32e.pcap"/>
<arg name="pcap" value="$(find velodyne_driver)/tests/32e.pcap"/>
</include>

<!-- verify PointCloud publication rate -->
Expand Down
2 changes: 1 addition & 1 deletion velodyne_driver/tests/pcap_node_hertz.test
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

<!-- start read with example PCAP file -->
<node pkg="velodyne_driver" type="velodyne_node" name="velodyne_node">
<param name="pcap" value="/tmp/velodyne_driver/tests/class.pcap"/>
<param name="pcap" value="$(find velodyne_driver)/tests/class.pcap"/>
</node>

<test test-name="pcap_hertz_test" pkg="rostest" type="hztest" name="hztest1" >
Expand Down
3 changes: 1 addition & 2 deletions velodyne_driver/tests/pcap_nodelet_hertz.test
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@

<!-- start nodelet manager, driver and pointcloud nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="pcap"
value="/tmp/velodyne_driver/tests/class.pcap"/>
<arg name="pcap" value="$(find velodyne_driver)/tests/class.pcap"/>
</include>

<!-- verify PointCloud publication rate -->
Expand Down
24 changes: 11 additions & 13 deletions velodyne_pointcloud/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,19 +45,17 @@ install(DIRECTORY include/${PROJECT_NAME}/
### TODO install some launch scripts and parameter files

# Download packet capture (PCAP) files containing test data.
#
# This package uses the same PCAP test files as velodyne_driver.
# Catkin assigns them the same target names, so they cannot be
# downloaded again in this package. As long as both packages are
# always built and tested together in the same repository, that works.
#
#download_test_data(http://pr.willowgarage.com/data/velodyne/class.pcap
# tests/class.pcap
# 65808d25772101358a3719b451b3d015)
#
#download_test_data(http://pr.willowgarage.com/data/velodyne/32e.pcap
# tests/32e.pcap
# e41d02aac34f0967c03a5597e1d554a9)
# Store them in devel-space, so rostest can easily find them.
catkin_download_test_data(
${PROJECT_NAME}_tests_class.pcap
http://pr.willowgarage.com/data/velodyne/class.pcap
DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/tests
MD5 65808d25772101358a3719b451b3d015)
catkin_download_test_data(
${PROJECT_NAME}_tests_32e.pcap
http://pr.willowgarage.com/data/velodyne/32e.pcap
DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/tests
MD5 e41d02aac34f0967c03a5597e1d554a9)

# unit tests
add_rostest(tests/cloud_node_hz.test)
Expand Down
2 changes: 1 addition & 1 deletion velodyne_pointcloud/tests/cloud_node_32e_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<!-- start driver with example PCAP file -->
<node pkg="velodyne_driver" type="velodyne_node" name="velodyne_node">
<param name="model" value="32E"/>
<param name="pcap" value="/tmp/velodyne_driver/tests/32e.pcap"/>
<param name="pcap" value="$(find velodyne_pointcloud)/tests/32e.pcap"/>
</node>

<!-- start cloud node with test calibration file -->
Expand Down
2 changes: 1 addition & 1 deletion velodyne_pointcloud/tests/cloud_node_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

<!-- start driver with example PCAP file -->
<node pkg="velodyne_driver" type="velodyne_node" name="velodyne_node">
<param name="pcap" value="/tmp/velodyne_driver/tests/class.pcap"/>
<param name="pcap" value="$(find velodyne_pointcloud)/tests/class.pcap"/>
</node>

<!-- start cloud node with test calibration file -->
Expand Down
3 changes: 1 addition & 2 deletions velodyne_pointcloud/tests/cloud_nodelet_32e_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="model" value="32E"/>
<arg name="pcap"
value="/tmp/velodyne_driver/tests/32e.pcap"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/32e.pcap"/>
</include>

<!-- start cloud nodelet using test calibration file -->
Expand Down
3 changes: 1 addition & 2 deletions velodyne_pointcloud/tests/cloud_nodelet_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@

<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="pcap"
value="/tmp/velodyne_driver/tests/class.pcap"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/class.pcap"/>
</include>

<!-- start cloud nodelet using test calibration file -->
Expand Down
2 changes: 1 addition & 1 deletion velodyne_pointcloud/tests/transform_node_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

<!-- start driver with example PCAP file -->
<node pkg="velodyne_driver" type="velodyne_node" name="velodyne_node">
<param name="pcap" value="/tmp/velodyne_driver/tests/class.pcap"/>
<param name="pcap" value="$(find velodyne_pointcloud)/tests/class.pcap"/>
</node>

<!-- start transform node with test calibration file -->
Expand Down
3 changes: 1 addition & 2 deletions velodyne_pointcloud/tests/transform_nodelet_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,7 @@

<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="pcap"
value="/tmp/velodyne_driver/tests/class.pcap"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/class.pcap"/>
</include>

<!-- start transform nodelet -->
Expand Down

0 comments on commit ac1f34b

Please sign in to comment.