From 1327e27475949ee6735ce0df35e1226bab9caa41 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 2 Nov 2017 09:47:43 +0100 Subject: [PATCH] fixup: run unittest in correct ROS context --- package.xml | 2 +- src/test/CMakeLists.txt | 3 ++- src/test/test_task_model.launch | 7 +++++++ 3 files changed, 10 insertions(+), 2 deletions(-) create mode 100644 src/test/test_task_model.launch diff --git a/package.xml b/package.xml index 35594541..9f89f2a4 100644 --- a/package.xml +++ b/package.xml @@ -19,7 +19,7 @@ moveit_msgs rviz - rosunit + rostest diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt index 346e2820..33feeab8 100644 --- a/src/test/CMakeLists.txt +++ b/src/test/CMakeLists.txt @@ -7,13 +7,14 @@ include_directories(${CMAKE_SOURCE_DIR}/src) ## Add gtest based cpp test target and link libraries if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) catkin_add_gtest(${PROJECT_NAME}-test-container test_container.cpp) target_link_libraries(${PROJECT_NAME}-test-container ${PROJECT_NAME} ${catkin_LIBRARIES} gtest_main) - catkin_add_gtest(${PROJECT_NAME}-test-task_model test_task_model.cpp) + add_rostest_gtest(${PROJECT_NAME}-test-task_model test_task_model.launch test_task_model.cpp) target_link_libraries(${PROJECT_NAME}-test-task_model motion_planning_tasks_rviz_plugin ${PROJECT_NAME}_stages diff --git a/src/test/test_task_model.launch b/src/test/test_task_model.launch new file mode 100644 index 00000000..01a154dc --- /dev/null +++ b/src/test/test_task_model.launch @@ -0,0 +1,7 @@ + + + + + +