Skip to content

Commit

Permalink
Enable global planner tester (#927)
Browse files Browse the repository at this point in the history
  • Loading branch information
orduno committed Aug 28, 2019
1 parent c27d663 commit 39ab506
Show file tree
Hide file tree
Showing 8 changed files with 190 additions and 120 deletions.
4 changes: 3 additions & 1 deletion nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ find_package(nav_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(gazebo_ros_pkgs REQUIRED)
find_package(nav2_amcl REQUIRED)
find_package(nav2_lifecycle_manager REQUIRED)
Expand All @@ -30,6 +31,7 @@ set(dependencies
gazebo_ros_pkgs
geometry_msgs
std_msgs
tf2_geometry_msgs
rclpy
)

Expand All @@ -40,7 +42,7 @@ if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)

# add_subdirectory(src/planning)
add_subdirectory(src/planning)
add_subdirectory(src/localization)
add_subdirectory(src/system)
add_subdirectory(src/updown)
Expand Down
2 changes: 2 additions & 0 deletions nav2_system_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<build_depend>launch_testing</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>gazebo_ros_pkgs</build_depend>
<build_depend>launch_ros</build_depend>
<build_depend>launch_testing</build_depend>
Expand All @@ -39,6 +40,7 @@
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>nav2_amcl</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>tf2_geometry_msgs</exec_depend>
<exec_depend>gazebo_ros_pkgs</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>launch_testing</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/src/planning/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ ament_target_dependencies(test_planner_node
${dependencies}
)

ament_add_test(test_planner_node
ament_add_test(test_planner
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_planner_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
Expand Down
Loading

0 comments on commit 39ab506

Please sign in to comment.