Skip to content

Commit

Permalink
make rostest in CMakeLists optional (ros/rosdistro#3010)
Browse files Browse the repository at this point in the history
  • Loading branch information
bulwahn authored and dirk-thomas committed Feb 27, 2014
1 parent dbc3c3e commit a7dd5d5
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 4 deletions.
3 changes: 2 additions & 1 deletion tools/rosnode/CMakeLists.txt
@@ -1,10 +1,11 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosnode)
find_package(catkin REQUIRED COMPONENTS rostest)
find_package(catkin REQUIRED)
catkin_package()

catkin_python_setup()

if(CATKIN_ENABLE_TESTING)
find_package(rostest)
add_rostest(test/rosnode.test)
endif()
3 changes: 2 additions & 1 deletion tools/rostopic/CMakeLists.txt
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(rostopic)
find_package(catkin REQUIRED COMPONENTS rostest)
find_package(catkin REQUIRED)
catkin_package()

catkin_python_setup()
Expand All @@ -9,5 +9,6 @@ catkin_install_python(PROGRAMS scripts/rostopic
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

if(CATKIN_ENABLE_TESTING)
find_package(rostest)
add_rostest(test/rostopic.test)
endif()
3 changes: 2 additions & 1 deletion tools/topic_tools/CMakeLists.txt
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(topic_tools)
find_package(catkin COMPONENTS cpp_common message_generation rosconsole roscpp rostest rostime rosunit std_msgs xmlrpcpp)
find_package(catkin COMPONENTS cpp_common message_generation rosconsole roscpp rostime std_msgs xmlrpcpp)

include_directories(include)
include_directories(${catkin_INCLUDE_DIRS})
Expand Down Expand Up @@ -62,6 +62,7 @@ catkin_install_python(PROGRAMS

#Testing
if(CATKIN_ENABLE_TESTING)
find_package(rostest rosunit)
catkin_add_gtest(${PROJECT_NAME}-utest test/utest.cpp)
if(TARGET ${PROJECT_NAME}-utest)
target_link_libraries(${PROJECT_NAME}-utest topic_tools)
Expand Down
3 changes: 2 additions & 1 deletion utilities/roswtf/CMakeLists.txt
@@ -1,10 +1,11 @@
cmake_minimum_required(VERSION 2.8.3)
project(roswtf)
find_package(catkin REQUIRED COMPONENTS rostest)
find_package(catkin REQUIRED)
catkin_package()
catkin_python_setup()

if(CATKIN_ENABLE_TESTING)
find_package(rostest)
add_rostest(test/roswtf.test)
catkin_add_nosetests(test)
endif()

0 comments on commit a7dd5d5

Please sign in to comment.