Skip to content

Commit

Permalink
Switch nav2_system_tests to modern CMake idioms. (#4638)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 22, 2024
1 parent 226b196 commit 8990c05
Show file tree
Hide file tree
Showing 18 changed files with 230 additions and 224 deletions.
176 changes: 84 additions & 92 deletions nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,114 +1,110 @@
cmake_minimum_required(VERSION 3.5)
project(nav2_system_tests)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 23)
endif()

find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_map_server REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
find_package(nav2_msgs REQUIRED)
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(nav2_amcl REQUIRED)
find_package(nav2_lifecycle_manager REQUIRED)
find_package(rclpy REQUIRED)
find_package(nav2_navfn_planner REQUIRED)
find_package(nav2_planner REQUIRED)
find_package(navigation2)
find_package(angles REQUIRED)
find_package(behaviortree_cpp REQUIRED)
find_package(pluginlib REQUIRED)
find_package(nav2_minimal_tb3_sim REQUIRED)

nav2_package()

set(dependencies
rclcpp
nav2_util
nav2_map_server
nav2_msgs
nav_msgs
visualization_msgs
nav2_amcl
nav2_lifecycle_manager
nav2_behavior_tree
geometry_msgs
std_msgs
tf2_geometry_msgs
rclpy
nav2_planner
nav2_navfn_planner
angles
behaviortree_cpp
pluginlib
)

set(local_controller_plugin_lib local_controller)

add_library(${local_controller_plugin_lib} SHARED src/error_codes/controller/controller_error_plugins.cpp)
ament_target_dependencies(${local_controller_plugin_lib} ${dependencies})
target_compile_definitions(${local_controller_plugin_lib} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
pluginlib_export_plugin_description_file(nav2_core src/error_codes/controller_plugins.xml)

install(TARGETS ${local_controller_plugin_lib}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(angles REQUIRED)
find_package(behaviortree_cpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_amcl REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
find_package(nav2_lifecycle_manager REQUIRED)
find_package(nav2_map_server REQUIRED)
find_package(nav2_minimal_tb3_sim REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_navfn_planner REQUIRED)
find_package(nav2_planner REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(navigation2 REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(visualization_msgs REQUIRED)

install(FILES src/error_codes/controller_plugins.xml
DESTINATION share/${PROJECT_NAME}
)
ament_lint_auto_find_test_dependencies()

ament_find_gtest()

set(global_planner_plugin_lib global_planner)
set(local_controller_plugin_lib local_controller)

add_library(${global_planner_plugin_lib} SHARED src/error_codes/planner/planner_error_plugin.cpp)
ament_target_dependencies(${global_planner_plugin_lib} ${dependencies})
target_compile_definitions(${global_planner_plugin_lib} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
pluginlib_export_plugin_description_file(nav2_core src/error_codes/planner_plugins.xml)
add_library(${local_controller_plugin_lib} SHARED src/error_codes/controller/controller_error_plugins.cpp)
target_link_libraries(${local_controller_plugin_lib} PRIVATE
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
pluginlib::pluginlib
)
pluginlib_export_plugin_description_file(nav2_core src/error_codes/controller_plugins.xml)

install(TARGETS ${global_planner_plugin_lib}
install(TARGETS ${local_controller_plugin_lib}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)
)

install(FILES src/error_codes/planner_plugins.xml
install(FILES src/error_codes/controller_plugins.xml
DESTINATION share/${PROJECT_NAME}
)

set(smoother_plugin_lib smoother)

add_library(${smoother_plugin_lib} SHARED src/error_codes/smoother/smoother_error_plugin.cpp)
ament_target_dependencies(${smoother_plugin_lib} ${dependencies})
target_compile_definitions(${smoother_plugin_lib} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
pluginlib_export_plugin_description_file(nav2_core src/error_codes/smoother_plugins.xml)

install(TARGETS ${smoother_plugin_lib}
)

set(global_planner_plugin_lib global_planner)

add_library(${global_planner_plugin_lib} SHARED src/error_codes/planner/planner_error_plugin.cpp)
target_link_libraries(${global_planner_plugin_lib} PRIVATE
${geometry_msgs_TARGETS}
nav2_core::nav2_core ${nav_msgs_TARGETS}
nav2_costmap_2d::nav2_costmap_2d_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)
pluginlib_export_plugin_description_file(nav2_core src/error_codes/planner_plugins.xml)

install(TARGETS ${global_planner_plugin_lib}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)
)

install(FILES src/error_codes/smoother_plugins.xml
install(FILES src/error_codes/planner_plugins.xml
DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
)

set(smoother_plugin_lib smoother)

add_library(${smoother_plugin_lib} SHARED src/error_codes/smoother/smoother_error_plugin.cpp)
target_link_libraries(${smoother_plugin_lib} PRIVATE
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)
pluginlib_export_plugin_description_file(nav2_core src/error_codes/smoother_plugins.xml)

install(TARGETS ${smoother_plugin_lib}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)
install(FILES src/error_codes/smoother_plugins.xml
DESTINATION share/${PROJECT_NAME}
)

add_subdirectory(src/behavior_tree)
add_subdirectory(src/planning)
Expand All @@ -126,10 +122,6 @@ if(BUILD_TESTING)
add_subdirectory(src/costmap_filters)
add_subdirectory(src/error_codes)
install(DIRECTORY maps models DESTINATION share/${PROJECT_NAME})

endif()

ament_export_libraries(${local_controller_plugin_lib})
ament_export_libraries(${global_planner_plugin_lib})
ament_export_libraries(${smoother_plugin_lib})
ament_package()
73 changes: 26 additions & 47 deletions nav2_system_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,58 +10,37 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<build_depend>rclcpp</build_depend>
<build_depend>rclpy</build_depend>
<build_depend>nav2_util</build_depend>
<build_depend>nav2_map_server</build_depend>
<build_depend>nav2_msgs</build_depend>
<build_depend>nav2_lifecycle_manager</build_depend>
<build_depend>nav2_navfn_planner</build_depend>
<build_depend>nav2_behavior_tree</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>visualization_msgs</build_depend>
<build_depend>nav2_amcl</build_depend>
<build_depend>launch_ros</build_depend>
<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>launch_ros</build_depend>
<build_depend>launch_testing</build_depend>
<build_depend>nav2_planner</build_depend>
<build_depend>nav2_minimal_tb3_sim</build_depend>

<exec_depend>launch_ros</exec_depend>
<exec_depend>launch_testing</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>nav2_bringup</exec_depend>
<exec_depend>nav2_util</exec_depend>
<exec_depend>nav2_map_server</exec_depend>
<exec_depend>nav2_msgs</exec_depend>
<exec_depend>nav2_lifecycle_manager</exec_depend>
<exec_depend>nav2_navfn_planner</exec_depend>
<exec_depend>nav2_behavior_tree</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>visualization_msgs</exec_depend>
<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>nav2_minimal_tb3_sim</exec_depend>
<exec_depend>navigation2</exec_depend>
<exec_depend>lcov</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>nav2_planner</exec_depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>geometry_msgs</test_depend>
<test_depend>launch</test_depend>
<test_depend>launch_ros</test_depend>
<test_depend>launch_testing</test_depend>
<test_depend>python3-zmq</test_depend>
<test_depend>lcov</test_depend>
<test_depend>nav2_amcl</test_depend>
<test_depend>nav2_behavior_tree</test_depend>
<test_depend>nav2_bringup</test_depend>
<test_depend>nav2_lifecycle_manager</test_depend>
<test_depend>nav2_map_server</test_depend>
<test_depend>nav2_minimal_tb3_sim</test_depend>
<test_depend>nav2_msgs</test_depend>
<test_depend>nav2_navfn_planner</test_depend>
<test_depend>nav2_planner</test_depend>
<test_depend>nav2_util</test_depend>
<test_depend>nav_msgs</test_depend>
<test_depend>navigation2</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>rclcpp_lifecycle</test_depend>
<test_depend>rclpy</test_depend>
<test_depend>robot_state_publisher</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>tf2</test_depend>
<test_depend>tf2_geometry_msgs</test_depend>
<test_depend>tf2_ros</test_depend>
<test_depend>visualization_msgs</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
18 changes: 8 additions & 10 deletions nav2_system_tests/src/behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,16 +1,14 @@
find_package(Boost COMPONENTS system filesystem REQUIRED)

ament_add_gtest(test_behavior_tree_node
test_behavior_tree_node.cpp
server_handler.cpp
)

ament_target_dependencies(test_behavior_tree_node
${dependencies}
)

target_include_directories(test_behavior_tree_node PUBLIC ${Boost_INCLUDE_DIRS})
target_link_libraries(test_behavior_tree_node
${Boost_FILESYSTEM_LIBRARY}
${Boost_SYSTEM_LIBRARY}
ament_index_cpp::ament_index_cpp
behaviortree_cpp::behaviortree_cpp
${geometry_msgs_TARGETS}
nav2_behavior_tree::nav2_behavior_tree
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
tf2_ros::tf2_ros
)
Loading

0 comments on commit 8990c05

Please sign in to comment.