From 71b5c52c8fd745a1a66dca0b8ee0bdfe4bc25786 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 7 Aug 2024 20:59:48 +0000 Subject: [PATCH] Switch dwb_plugins to modern CMake idioms. Signed-off-by: Chris Lalancette --- .../dwb_plugins/CMakeLists.txt | 75 ++++++++++++------- .../include/dwb_plugins/velocity_iterator.hpp | 1 - nav2_dwb_controller/dwb_plugins/package.xml | 10 ++- .../dwb_plugins/test/CMakeLists.txt | 25 ++++++- 4 files changed, 76 insertions(+), 35 deletions(-) diff --git a/nav2_dwb_controller/dwb_plugins/CMakeLists.txt b/nav2_dwb_controller/dwb_plugins/CMakeLists.txt index a1806c524a..75a00b9b7f 100644 --- a/nav2_dwb_controller/dwb_plugins/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_plugins/CMakeLists.txt @@ -2,38 +2,41 @@ cmake_minimum_required(VERSION 3.5) project(dwb_plugins) find_package(ament_cmake REQUIRED) -find_package(nav2_common REQUIRED) -find_package(angles REQUIRED) find_package(dwb_core REQUIRED) +find_package(dwb_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(nav2_common REQUIRED) +find_package(nav2_util REQUIRED) find_package(nav_2d_msgs REQUIRED) find_package(nav_2d_utils REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) -find_package(nav2_util REQUIRED) +find_package(rcl_interfaces REQUIRED) nav2_package() -set(dependencies - angles - dwb_core - nav_2d_msgs - nav_2d_utils - pluginlib - rclcpp - nav2_util +add_library(standard_traj_generator SHARED + src/standard_traj_generator.cpp + src/limited_accel_generator.cpp + src/kinematic_parameters.cpp + src/xy_theta_iterator.cpp) +target_include_directories(standard_traj_generator PUBLIC + "$" + "$" ) - -include_directories( - include +target_link_libraries(standard_traj_generator PUBLIC + dwb_core::dwb_core + ${dwb_msgs_TARGETS} + ${geometry_msgs_TARGETS} + nav2_util::nav2_util_core + ${nav_2d_msgs_TARGETS} + rclcpp::rclcpp + ${rcl_interfaces_TARGETS} +) +target_link_libraries(standard_traj_generator PRIVATE + nav_2d_utils::conversions + pluginlib::pluginlib ) - -add_library(standard_traj_generator SHARED - src/standard_traj_generator.cpp - src/limited_accel_generator.cpp - src/kinematic_parameters.cpp - src/xy_theta_iterator.cpp) -ament_target_dependencies(standard_traj_generator ${dependencies}) - if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) @@ -42,23 +45,39 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() find_package(ament_cmake_gtest REQUIRED) + ament_find_gtest() + + find_package(nav2_costmap_2d REQUIRED) + find_package(rclcpp_lifecycle REQUIRED) add_subdirectory(test) endif() install(TARGETS standard_traj_generator - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin ) install(DIRECTORY include/ - DESTINATION include/ + DESTINATION include/${PROJECT_NAME} ) install(FILES plugins.xml - DESTINATION share/${PROJECT_NAME} + DESTINATION share/${PROJECT_NAME} ) -ament_export_include_directories(include) +ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(standard_traj_generator) +ament_export_dependencies( + dwb_core + dwb_msgs + geometry_msgs + nav2_util + nav_2d_msgs + rclcpp + rcl_interfaces +) +ament_export_targets(${PROJECT_NAME}) + pluginlib_export_plugin_description_file(dwb_core plugins.xml) ament_package() diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp index 55a663fddb..e5feefc9fa 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp @@ -38,7 +38,6 @@ #include #include -#include "rclcpp/rclcpp.hpp" #include "nav_2d_msgs/msg/twist2_d.hpp" #include "dwb_plugins/kinematic_parameters.hpp" #include "nav2_util/lifecycle_node.hpp" diff --git a/nav2_dwb_controller/dwb_plugins/package.xml b/nav2_dwb_controller/dwb_plugins/package.xml index 86311cfb56..3e0b0c941e 100644 --- a/nav2_dwb_controller/dwb_plugins/package.xml +++ b/nav2_dwb_controller/dwb_plugins/package.xml @@ -12,17 +12,21 @@ ament_cmake nav2_common - angles dwb_core + dwb_msgs + geometry_msgs + nav2_util nav_2d_msgs nav_2d_utils pluginlib rclcpp - nav2_util + rcl_interfaces + ament_cmake_gtest ament_lint_common ament_lint_auto - ament_cmake_gtest + nav2_costmap_2d + rclcpp_lifecycle ament_cmake diff --git a/nav2_dwb_controller/dwb_plugins/test/CMakeLists.txt b/nav2_dwb_controller/dwb_plugins/test/CMakeLists.txt index c5b9308e8d..a785393843 100644 --- a/nav2_dwb_controller/dwb_plugins/test/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_plugins/test/CMakeLists.txt @@ -1,10 +1,29 @@ ament_add_gtest(vtest velocity_iterator_test.cpp) +target_link_libraries(vtest standard_traj_generator) ament_add_gtest(twist_gen_test twist_gen.cpp) -target_link_libraries(twist_gen_test standard_traj_generator) +target_link_libraries(twist_gen_test + standard_traj_generator + dwb_core::dwb_core + ${dwb_msgs_TARGETS} + ${geometry_msgs_TARGETS} + nav2_util::nav2_util_core + ${nav_2d_msgs_TARGETS} + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle +) ament_add_gtest(kinematic_parameters_test kinematic_parameters_test.cpp) -target_link_libraries(kinematic_parameters_test standard_traj_generator) +target_link_libraries(kinematic_parameters_test + standard_traj_generator + rclcpp::rclcpp + ${rcl_interfaces_TARGETS} +) ament_add_gtest(speed_limit_test speed_limit_test.cpp) -target_link_libraries(speed_limit_test standard_traj_generator) +target_link_libraries(speed_limit_test + standard_traj_generator + nav2_costmap_2d::nav2_costmap_2d_core + nav2_util::nav2_util_core + rclcpp::rclcpp +)