From 8990c05992e7f1d7ea02fc32a5ab4355ed77d3ca Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 22 Aug 2024 13:08:11 -0400 Subject: [PATCH] Switch nav2_system_tests to modern CMake idioms. (#4638) Signed-off-by: Chris Lalancette --- nav2_system_tests/CMakeLists.txt | 176 +++++++++--------- nav2_system_tests/package.xml | 73 +++----- .../src/behavior_tree/CMakeLists.txt | 18 +- .../behavior_tree/test_behavior_tree_node.cpp | 35 ++-- .../behaviors/assisted_teleop/CMakeLists.txt | 14 +- .../assisted_teleop_behavior_tester.hpp | 1 - .../src/behaviors/wait/CMakeLists.txt | 12 +- .../behaviors/wait/wait_behavior_tester.hpp | 1 - .../src/dummy_controller/CMakeLists.txt | 15 +- .../src/dummy_planner/CMakeLists.txt | 13 +- .../src/localization/CMakeLists.txt | 6 +- .../localization/test_localization_node.cpp | 6 +- nav2_system_tests/src/planning/CMakeLists.txt | 68 +++++-- .../src/planning/planner_tester.hpp | 3 - .../planning/test_planner_is_path_valid.cpp | 1 + .../src/planning/test_planner_plugins.cpp | 2 + nav2_system_tests/src/updown/CMakeLists.txt | 8 +- nav2_system_tests/src/updown/test_updown.cpp | 2 +- 18 files changed, 230 insertions(+), 224 deletions(-) diff --git a/nav2_system_tests/CMakeLists.txt b/nav2_system_tests/CMakeLists.txt index 127986f464b..851a1e2db40 100644 --- a/nav2_system_tests/CMakeLists.txt +++ b/nav2_system_tests/CMakeLists.txt @@ -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) @@ -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() diff --git a/nav2_system_tests/package.xml b/nav2_system_tests/package.xml index e3472e3e94c..05046c8d8a3 100644 --- a/nav2_system_tests/package.xml +++ b/nav2_system_tests/package.xml @@ -10,58 +10,37 @@ ament_cmake nav2_common - rclcpp - rclpy - nav2_util - nav2_map_server - nav2_msgs - nav2_lifecycle_manager - nav2_navfn_planner - nav2_behavior_tree - nav_msgs - visualization_msgs - nav2_amcl - launch_ros - launch_testing - geometry_msgs - std_msgs - tf2_geometry_msgs - launch_ros - launch_testing - nav2_planner - nav2_minimal_tb3_sim - - launch_ros - launch_testing - rclcpp - rclpy - nav2_bringup - nav2_util - nav2_map_server - nav2_msgs - nav2_lifecycle_manager - nav2_navfn_planner - nav2_behavior_tree - nav_msgs - visualization_msgs - geometry_msgs - nav2_amcl - std_msgs - tf2_geometry_msgs - nav2_minimal_tb3_sim - navigation2 - lcov - robot_state_publisher - nav2_planner - - ament_lint_common - ament_lint_auto ament_cmake_gtest ament_cmake_pytest + ament_index_cpp + ament_lint_auto + ament_lint_common + geometry_msgs launch launch_ros launch_testing - python3-zmq + lcov + nav2_amcl + nav2_behavior_tree + nav2_bringup + nav2_lifecycle_manager + nav2_map_server + nav2_minimal_tb3_sim + nav2_msgs + nav2_navfn_planner + nav2_planner + nav2_util + nav_msgs + navigation2 + rclcpp + rclcpp_lifecycle + rclpy + robot_state_publisher + std_msgs + tf2 + tf2_geometry_msgs + tf2_ros + visualization_msgs ament_cmake diff --git a/nav2_system_tests/src/behavior_tree/CMakeLists.txt b/nav2_system_tests/src/behavior_tree/CMakeLists.txt index 19eca116e07..66d4fb1e1fb 100644 --- a/nav2_system_tests/src/behavior_tree/CMakeLists.txt +++ b/nav2_system_tests/src/behavior_tree/CMakeLists.txt @@ -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 ) diff --git a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp index 100e5dad936..d8c0070d134 100644 --- a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp +++ b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#include -#include +#include #include +#include #include +#include #include -#include -#include +#include #include "gtest/gtest.h" @@ -31,16 +31,18 @@ #include "tf2_ros/create_timer_ros.h" #include "nav2_util/odometry_utils.hpp" +#include "nav2_util/string_utils.hpp" #include "nav2_behavior_tree/plugins_list.hpp" #include "rclcpp/rclcpp.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" + #include "server_handler.hpp" using namespace std::chrono_literals; -namespace fs = boost::filesystem; namespace nav2_system_tests { @@ -61,8 +63,7 @@ class BehaviorTreeHandler odom_smoother_ = std::make_shared(node_); - std::vector plugin_libs; - boost::split(plugin_libs, nav2::details::BT_BUILTIN_PLUGINS, boost::is_any_of(";")); + nav2_util::Tokens plugin_libs = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';'); for (const auto & p : plugin_libs) { factory_.registerFromPlugin(BT::SharedLibrary::getOSName(p)); @@ -194,12 +195,12 @@ std::shared_ptr BehaviorTreeTestFixture::bt_handler = nullp TEST_F(BehaviorTreeTestFixture, TestBTXMLFiles) { - fs::path root = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path root = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); root /= "behavior_trees/"; - if (boost::filesystem::exists(root) && boost::filesystem::is_directory(root)) { - for (auto const & entry : boost::filesystem::recursive_directory_iterator(root)) { - if (boost::filesystem::is_regular_file(entry) && entry.path().extension() == ".xml") { + if (std::filesystem::exists(root) && std::filesystem::is_directory(root)) { + for (auto const & entry : std::filesystem::recursive_directory_iterator(root)) { + if (std::filesystem::is_regular_file(entry) && entry.path().extension() == ".xml") { std::cout << entry.path().string() << std::endl; EXPECT_EQ(bt_handler->loadBehaviorTree(entry.path().string()), true); } @@ -216,7 +217,7 @@ TEST_F(BehaviorTreeTestFixture, TestBTXMLFiles) TEST_F(BehaviorTreeTestFixture, TestAllSuccess) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); @@ -258,7 +259,7 @@ TEST_F(BehaviorTreeTestFixture, TestAllSuccess) TEST_F(BehaviorTreeTestFixture, TestAllFailure) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); @@ -310,7 +311,7 @@ TEST_F(BehaviorTreeTestFixture, TestAllFailure) TEST_F(BehaviorTreeTestFixture, TestNavigateSubtreeRecoveries) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); @@ -364,7 +365,7 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateSubtreeRecoveries) TEST_F(BehaviorTreeTestFixture, TestNavigateRecoverySimple) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); @@ -458,7 +459,7 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoverySimple) TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); @@ -522,7 +523,7 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex) TEST_F(BehaviorTreeTestFixture, TestRecoverySubtreeGoalUpdated) { // Load behavior tree from file - fs::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); + std::filesystem::path bt_file = ament_index_cpp::get_package_share_directory("nav2_bt_navigator"); bt_file /= "behavior_trees/"; bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt b/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt index 740bb774913..0bc3240cc83 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt +++ b/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt @@ -4,9 +4,17 @@ ament_add_gtest_executable(${test_assisted_teleop_behavior} test_assisted_teleop_behavior_node.cpp assisted_teleop_behavior_tester.cpp ) - -ament_target_dependencies(${test_assisted_teleop_behavior} - ${dependencies} +target_link_libraries(${test_assisted_teleop_behavior} + ${geometry_msgs_TARGETS} + nav2_costmap_2d::nav2_costmap_2d_core + nav2_costmap_2d::nav2_costmap_2d_client + nav2_util::nav2_util_core + ${nav2_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + ${std_msgs_TARGETS} + tf2::tf2 + tf2_ros::tf2_ros ) ament_add_test(test_assisted_teleop_behavior diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp index 2cf46827e89..37bdd790c2c 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp @@ -22,7 +22,6 @@ #include #include -#include "angles/angles.h" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" #include "geometry_msgs/msg/twist.hpp" diff --git a/nav2_system_tests/src/behaviors/wait/CMakeLists.txt b/nav2_system_tests/src/behaviors/wait/CMakeLists.txt index 36bf50dec8e..5e2d4d656be 100644 --- a/nav2_system_tests/src/behaviors/wait/CMakeLists.txt +++ b/nav2_system_tests/src/behaviors/wait/CMakeLists.txt @@ -4,9 +4,15 @@ ament_add_gtest_executable(${test_wait_behavior_exec} test_wait_behavior_node.cpp wait_behavior_tester.cpp ) - -ament_target_dependencies(${test_wait_behavior_exec} - ${dependencies} +target_link_libraries(${test_wait_behavior_exec} + angles::angles + ${geometry_msgs_TARGETS} + ${nav2_msgs_TARGETS} + nav2_util::nav2_util_core + rclcpp::rclcpp + rclcpp_action::rclcpp_action + tf2::tf2 + tf2_ros::tf2_ros ) ament_add_test(test_wait_behavior diff --git a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp index 71181e24d36..18e131de88b 100644 --- a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp @@ -25,7 +25,6 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" -#include "angles/angles.h" #include "nav2_msgs/action/wait.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/node_thread.hpp" diff --git a/nav2_system_tests/src/dummy_controller/CMakeLists.txt b/nav2_system_tests/src/dummy_controller/CMakeLists.txt index c552f861c9d..688234b2a8a 100644 --- a/nav2_system_tests/src/dummy_controller/CMakeLists.txt +++ b/nav2_system_tests/src/dummy_controller/CMakeLists.txt @@ -2,12 +2,9 @@ add_executable(dummy_controller_node src/dummy_controller/main.cpp src/dummy_controller/dummy_controller.cpp ) - -ament_target_dependencies(dummy_controller_node - rclcpp - std_msgs - nav2_util - nav2_behavior_tree - nav2_msgs - nav_msgs -) \ No newline at end of file +target_link_libraries(dummy_controller_node PRIVATE + ${geometry_msgs_TARGETS} + nav2_behavior_tree::nav2_behavior_tree + nav2_util::nav2_util_core + rclcpp::rclcpp +) diff --git a/nav2_system_tests/src/dummy_planner/CMakeLists.txt b/nav2_system_tests/src/dummy_planner/CMakeLists.txt index b1b4c66a761..14fada8fcc6 100644 --- a/nav2_system_tests/src/dummy_planner/CMakeLists.txt +++ b/nav2_system_tests/src/dummy_planner/CMakeLists.txt @@ -2,12 +2,7 @@ add_executable(dummy_planner_node src/dummy_planner/main.cpp src/dummy_planner/dummy_planner.cpp ) - -ament_target_dependencies(dummy_planner_node - rclcpp - std_msgs - nav2_util - nav2_behavior_tree - nav2_msgs - nav_msgs -) \ No newline at end of file +target_link_libraries(dummy_planner_node PRIVATE + nav2_behavior_tree::nav2_behavior_tree + rclcpp::rclcpp +) diff --git a/nav2_system_tests/src/localization/CMakeLists.txt b/nav2_system_tests/src/localization/CMakeLists.txt index 7fa35172c3b..9b5a9201419 100644 --- a/nav2_system_tests/src/localization/CMakeLists.txt +++ b/nav2_system_tests/src/localization/CMakeLists.txt @@ -1,11 +1,11 @@ ament_add_gtest_executable(test_localization_node test_localization_node.cpp ) -ament_target_dependencies(test_localization_node - ${dependencies} +target_link_libraries(test_localization_node + ${geometry_msgs_TARGETS} + rclcpp::rclcpp ) - ament_add_test(test_localization GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_localization_launch.py" diff --git a/nav2_system_tests/src/localization/test_localization_node.cpp b/nav2_system_tests/src/localization/test_localization_node.cpp index 092b5e9e84e..75c69ca506b 100644 --- a/nav2_system_tests/src/localization/test_localization_node.cpp +++ b/nav2_system_tests/src/localization/test_localization_node.cpp @@ -15,12 +15,10 @@ #include #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_amcl/amcl_node.hpp" -#include "std_msgs/msg/string.hpp" #include "geometry_msgs/msg/pose_array.hpp" +#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -using std::placeholders::_1; using namespace std::chrono_literals; // rclcpp::init can only be called once per process, so this needs to be a global variable @@ -52,7 +50,7 @@ class TestAmclPose : public ::testing::Test "initialpose", rclcpp::SystemDefaultsQoS()); subscription_ = node->create_subscription( "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&TestAmclPose::amcl_pose_callback, this, _1)); + std::bind(&TestAmclPose::amcl_pose_callback, this, std::placeholders::_1)); initial_pose_pub_->publish(testPose_); } diff --git a/nav2_system_tests/src/planning/CMakeLists.txt b/nav2_system_tests/src/planning/CMakeLists.txt index ed150c70408..2a0e9137e07 100644 --- a/nav2_system_tests/src/planning/CMakeLists.txt +++ b/nav2_system_tests/src/planning/CMakeLists.txt @@ -4,12 +4,18 @@ ament_add_gtest_executable(${test_planner_costmaps_exec} test_planner_costmaps_node.cpp planner_tester.cpp ) - target_link_libraries(${test_planner_costmaps_exec} - ${nav2_map_server_LIBRARIES}) - -ament_target_dependencies(${test_planner_costmaps_exec} - ${dependencies} + ${geometry_msgs_TARGETS} + nav2_map_server::map_io + nav2_map_server::map_server_core + ${nav2_msgs_TARGETS} + nav2_planner::planner_server_core + nav2_util::nav2_util_core + ${nav_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + ${visualization_msgs_TARGETS} ) set(test_planner_random_exec test_planner_random_node) @@ -18,13 +24,19 @@ ament_add_gtest_executable(${test_planner_random_exec} test_planner_random_node.cpp planner_tester.cpp ) - -ament_target_dependencies(${test_planner_random_exec} - ${dependencies} -) - target_link_libraries(${test_planner_random_exec} - ${nav2_map_server_LIBRARIES}) + ${geometry_msgs_TARGETS} + nav2_map_server::map_io + nav2_map_server::map_server_core + ${nav2_msgs_TARGETS} + nav2_planner::planner_server_core + nav2_util::nav2_util_core + ${nav_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + ${visualization_msgs_TARGETS} +) ament_add_test(test_planner_costmaps GENERATE_RESULT_FOR_RETURN_CODE_ZERO @@ -47,14 +59,36 @@ ament_add_test(test_planner_random ) ament_add_gtest(test_planner_plugins + planner_tester.cpp test_planner_plugins.cpp TIMEOUT 10 ) - -ament_target_dependencies(test_planner_plugins rclcpp geometry_msgs nav2_msgs ${dependencies}) +target_link_libraries(test_planner_plugins + ${geometry_msgs_TARGETS} + nav2_core::nav2_core + nav2_map_server::map_io + nav2_map_server::map_server_core + ${nav2_msgs_TARGETS} + nav2_planner::planner_server_core + nav2_util::nav2_util_core + ${nav_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros +) ament_add_gtest(test_planner_is_path_valid - test_planner_is_path_valid.cpp - planner_tester.cpp) - -ament_target_dependencies(test_planner_is_path_valid rclcpp geometry_msgs nav2_msgs ${dependencies}) + planner_tester.cpp + test_planner_is_path_valid.cpp +) +target_link_libraries(test_planner_is_path_valid + ${geometry_msgs_TARGETS} + nav2_map_server::map_io + nav2_map_server::map_server_core + ${nav2_msgs_TARGETS} + nav2_planner::planner_server_core + nav2_util::nav2_util_core + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros +) diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index 421a00f4b7d..03081726000 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -22,18 +22,15 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_action/rclcpp_action.hpp" #include "nav2_msgs/action/compute_path_to_pose.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "nav2_msgs/msg/costmap.hpp" #include "nav2_msgs/srv/get_costmap.hpp" #include "nav2_msgs/srv/is_path_valid.hpp" -#include "visualization_msgs/msg/marker.hpp" #include "nav2_util/costmap.hpp" #include "nav2_util/node_thread.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" -#include "tf2_msgs/msg/tf_message.hpp" #include "nav2_planner/planner_server.hpp" #include "tf2_ros/transform_broadcaster.h" diff --git a/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp b/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp index 958891e02ad..cf4b7c90a8a 100644 --- a/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp +++ b/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp @@ -16,6 +16,7 @@ #include #include +#include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_msgs/srv/is_path_valid.hpp" #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" diff --git a/nav2_system_tests/src/planning/test_planner_plugins.cpp b/nav2_system_tests/src/planning/test_planner_plugins.cpp index 0ae08f4fa9c..188db2474d5 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -17,6 +17,8 @@ #include #include +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" #include "nav2_util/lifecycle_utils.hpp" diff --git a/nav2_system_tests/src/updown/CMakeLists.txt b/nav2_system_tests/src/updown/CMakeLists.txt index 273e1828ea5..a6260ff35e0 100644 --- a/nav2_system_tests/src/updown/CMakeLists.txt +++ b/nav2_system_tests/src/updown/CMakeLists.txt @@ -1,11 +1,11 @@ add_executable(test_updown test_updown.cpp ) - -ament_target_dependencies(test_updown - ${dependencies} +target_link_libraries(test_updown PRIVATE + ${geometry_msgs_TARGETS} + nav2_lifecycle_manager::nav2_lifecycle_manager_core + rclcpp::rclcpp ) install(TARGETS test_updown RUNTIME DESTINATION lib/${PROJECT_NAME}) install(FILES test_updown_launch.py DESTINATION share/${PROJECT_NAME}) - diff --git a/nav2_system_tests/src/updown/test_updown.cpp b/nav2_system_tests/src/updown/test_updown.cpp index 092e0edf46d..219a217cb67 100644 --- a/nav2_system_tests/src/updown/test_updown.cpp +++ b/nav2_system_tests/src/updown/test_updown.cpp @@ -19,7 +19,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp" -#include "rcutils/cmdline_parser.h" +#include "rclcpp/rclcpp.hpp" using namespace std::chrono_literals;