mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
fixup: run unittest in correct ROS context
This commit is contained in:
parent
6ba66b51a7
commit
1327e27475
@ -19,7 +19,7 @@
|
|||||||
<run_depend>moveit_msgs</run_depend>
|
<run_depend>moveit_msgs</run_depend>
|
||||||
<run_depend>rviz</run_depend>
|
<run_depend>rviz</run_depend>
|
||||||
|
|
||||||
<test_depend>rosunit</test_depend>
|
<test_depend>rostest</test_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<rviz plugin="${prefix}/motion_planning_tasks_rviz_plugin_description.xml"/>
|
<rviz plugin="${prefix}/motion_planning_tasks_rviz_plugin_description.xml"/>
|
||||||
|
|||||||
@ -7,13 +7,14 @@ include_directories(${CMAKE_SOURCE_DIR}/src)
|
|||||||
|
|
||||||
## Add gtest based cpp test target and link libraries
|
## Add gtest based cpp test target and link libraries
|
||||||
if (CATKIN_ENABLE_TESTING)
|
if (CATKIN_ENABLE_TESTING)
|
||||||
|
find_package(rostest REQUIRED)
|
||||||
catkin_add_gtest(${PROJECT_NAME}-test-container test_container.cpp)
|
catkin_add_gtest(${PROJECT_NAME}-test-container test_container.cpp)
|
||||||
target_link_libraries(${PROJECT_NAME}-test-container
|
target_link_libraries(${PROJECT_NAME}-test-container
|
||||||
${PROJECT_NAME}
|
${PROJECT_NAME}
|
||||||
${catkin_LIBRARIES}
|
${catkin_LIBRARIES}
|
||||||
gtest_main)
|
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
|
target_link_libraries(${PROJECT_NAME}-test-task_model
|
||||||
motion_planning_tasks_rviz_plugin
|
motion_planning_tasks_rviz_plugin
|
||||||
${PROJECT_NAME}_stages
|
${PROJECT_NAME}_stages
|
||||||
|
|||||||
7
src/test/test_task_model.launch
Normal file
7
src/test/test_task_model.launch
Normal 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>
|
||||||
Loading…
Reference in New Issue
Block a user