fixup: run unittest in correct ROS context

This commit is contained in:
Robert Haschke 2017-11-02 09:47:43 +01:00
parent 6ba66b51a7
commit 1327e27475
3 changed files with 10 additions and 2 deletions

View File

@ -19,7 +19,7 @@
<run_depend>moveit_msgs</run_depend>
<run_depend>rviz</run_depend>
<test_depend>rosunit</test_depend>
<test_depend>rostest</test_depend>
<export>
<rviz plugin="${prefix}/motion_planning_tasks_rviz_plugin_description.xml"/>

View File

@ -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

View File

@ -0,0 +1,7 @@
<launch>
<include file="$(find moveit_resources)/fanuc_moveit_config/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<test pkg="moveit_task_constructor"
type="moveit_task_constructor-test-task_model" test-name="test_task_model" />
</launch>