Skip to content

Commit

Permalink
check for CATKIN_ENABLE_TESTING
Browse files Browse the repository at this point in the history
  • Loading branch information
bulwahn committed Oct 14, 2013
1 parent 0b05a66 commit 8354ca3
Show file tree
Hide file tree
Showing 10 changed files with 54 additions and 43 deletions.
30 changes: 16 additions & 14 deletions base_local_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -125,17 +125,19 @@ install(DIRECTORY include/${PROJECT_NAME}/
PATTERN ".svn" EXCLUDE
)

catkin_add_gtest(base_local_planner_utest
test/gtest_main.cpp
test/utest.cpp
test/velocity_iterator_test.cpp
test/footprint_helper_test.cpp
test/trajectory_generator_test.cpp
test/map_grid_test.cpp)
target_link_libraries(base_local_planner_utest
base_local_planner trajectory_planner_ros
)


catkin_add_gtest(line_iterator
test/line_iterator_test.cpp)
if(CATKIN_ENABLE_TESTING)
catkin_add_gtest(base_local_planner_utest
test/gtest_main.cpp
test/utest.cpp
test/velocity_iterator_test.cpp
test/footprint_helper_test.cpp
test/trajectory_generator_test.cpp
test/map_grid_test.cpp)
target_link_libraries(base_local_planner_utest
base_local_planner trajectory_planner_ros
)


catkin_add_gtest(line_iterator
test/line_iterator_test.cpp)
endif()
2 changes: 1 addition & 1 deletion base_local_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<license>BSD</license>
<url>http://wiki.ros.org/base_local_planner</url>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>std_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
Expand Down
39 changes: 21 additions & 18 deletions map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,12 @@ target_link_libraries(map_server
${catkin_LIBRARIES}
)

add_executable(map_server-map_saver src/map_saver.cpp)
set_target_properties(map_server-map_saver PROPERTIES OUTPUT_NAME map_saver)
target_link_libraries(map_server-map_saver
${catkin_LIBRARIES}
)

# copy test data to same place as tests are run
function(copy_test_data)
cmake_parse_arguments(PROJECT "" "" "FILES" ${ARGN})
Expand All @@ -40,26 +46,23 @@ function(copy_test_data)
endforeach()
endfunction()

copy_test_data( FILES
test/testmap.bmp
test/testmap.png )
catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp test/test_constants.cpp)
target_link_libraries(${PROJECT_NAME}_utest image_loader SDL SDL_image)

add_executable(rtest test/rtest.cpp test/test_constants.cpp)
target_link_libraries( rtest
gtest
${catkin_LIBRARIES}
)
add_dependencies(rtest nav_msgs_gencpp)
## Tests
if(CATKIN_ENABLE_TESTING)
copy_test_data( FILES
test/testmap.bmp
test/testmap.png )
catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp test/test_constants.cpp)
target_link_libraries(${PROJECT_NAME}_utest image_loader SDL SDL_image)

add_executable(map_server-map_saver src/map_saver.cpp)
set_target_properties(map_server-map_saver PROPERTIES OUTPUT_NAME map_saver)
target_link_libraries(map_server-map_saver
${catkin_LIBRARIES}
)
add_executable(rtest test/rtest.cpp test/test_constants.cpp)
target_link_libraries( rtest
gtest
${catkin_LIBRARIES}
)
add_dependencies(rtest nav_msgs_gencpp)

add_rostest(test/rtest.xml)
add_rostest(test/rtest.xml)
endif()

## Install executables and/or libraries
install(TARGETS map_server-map_saver map_server image_loader
Expand Down
2 changes: 1 addition & 1 deletion map_server/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<url>http://wiki.ros.org/map_server</url>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
Expand Down
4 changes: 3 additions & 1 deletion navfn/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -121,4 +121,6 @@ endif (NAVFN_HAVE_FLTK AND NAVFN_HAVE_NETPBM AND NOT APPLE)
# message (STATUS "pgm.h not found (optional)")
# endif (NAVFN_HAVE_NETPBM)

add_subdirectory(test)
if(CATKIN_ENABLE_TESTING)
add_subdirectory(test)
endif()
2 changes: 1 addition & 1 deletion navfn/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<license>BSD</license>
<url>http://wiki.ros.org/navfn</url>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>costmap_2d</build_depend>
<build_depend>geometry_msgs</build_depend>
Expand Down
2 changes: 2 additions & 0 deletions robot_pose_ekf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ install(
## Tests are failing on OSX for an unknown reason
include(CMakeDetermineSystem)
if(CMAKE_SYSTEM_NAME MATCHES "Linux")
if(CATKIN_ENABLE_TESTING)

catkin_download_test_data(download_data_ekf_test2_indexed.bag http://download.ros.org/data/robot_pose_ekf/ekf_test2_indexed.bag FILENAME test/ekf_test2.bag MD5 71addef0ed900e05b301e0b4fdca99e2)
add_executable(test_robot_pose_ekf test/test_robot_pose_ekf.cpp)
Expand All @@ -98,4 +99,5 @@ target_link_libraries(test_robot_pose_ekf_zero_covariance
)
add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test_robot_pose_ekf_zero_covariance.launch)

endif(CATKIN_ENABLE_TESTING)
endif(CMAKE_SYSTEM_NAME MATCHES "Linux")
2 changes: 1 addition & 1 deletion robot_pose_ekf/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<license>BSD</license>
<url>http://wiki.ros.org/robot_pose_ekf</url>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
Expand Down
12 changes: 7 additions & 5 deletions voxel_grid/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,10 @@ install(DIRECTORY include/${PROJECT_NAME}/
PATTERN ".svn" EXCLUDE
)

catkin_add_gtest(voxel_grid_tests test/voxel_grid_tests.cpp)
target_link_libraries(voxel_grid_tests
voxel_grid
${catkin_LIBRARIES}
)
if(CATKIN_ENABLE_TESTING)
catkin_add_gtest(voxel_grid_tests test/voxel_grid_tests.cpp)
target_link_libraries(voxel_grid_tests
voxel_grid
${catkin_LIBRARIES}
)
endif()
2 changes: 1 addition & 1 deletion voxel_grid/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<license>BSD</license>
<url>http://wiki.ros.org/voxel_grid</url>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>

<build_depend>roscpp</build_depend>

Expand Down

0 comments on commit 8354ca3

Please sign in to comment.