From 123bc6c88bc4ef061e6a4b446b32a12a5b627cd4 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Mon, 5 Aug 2024 12:11:29 +0000 Subject: [PATCH] Switch nav2_rotation_shim_controller to modern CMake idioms. Signed-off-by: Chris Lalancette --- nav2_rotation_shim_controller/CMakeLists.txt | 69 +++++++++++-------- .../nav2_rotation_shim_controller.hpp | 4 -- nav2_rotation_shim_controller/package.xml | 13 ++-- .../src/nav2_rotation_shim_controller.cpp | 5 ++ .../test/CMakeLists.txt | 9 +-- 5 files changed, 60 insertions(+), 40 deletions(-) diff --git a/nav2_rotation_shim_controller/CMakeLists.txt b/nav2_rotation_shim_controller/CMakeLists.txt index 2e141d5f44..fafa98863c 100644 --- a/nav2_rotation_shim_controller/CMakeLists.txt +++ b/nav2_rotation_shim_controller/CMakeLists.txt @@ -2,53 +2,56 @@ cmake_minimum_required(VERSION 3.5) project(nav2_rotation_shim_controller) find_package(ament_cmake REQUIRED) +find_package(angles REQUIRED) +find_package(geometry_msgs REQUIRED) find_package(nav2_common REQUIRED) find_package(nav2_core REQUIRED) find_package(nav2_costmap_2d REQUIRED) find_package(nav2_util REQUIRED) -find_package(rclcpp REQUIRED) -find_package(geometry_msgs REQUIRED) find_package(nav_msgs REQUIRED) find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(rcl_interfaces REQUIRED) find_package(tf2 REQUIRED) -find_package(angles REQUIRED) +find_package(tf2_ros REQUIRED) nav2_package() -set(CMAKE_CXX_STANDARD 17) - -include_directories( - include -) - -set(dependencies - rclcpp - geometry_msgs - nav2_costmap_2d - pluginlib - nav_msgs - nav2_util - nav2_core - tf2 - angles -) set(library_name nav2_rotation_shim_controller) add_library(${library_name} SHARED - src/nav2_rotation_shim_controller.cpp) - -ament_target_dependencies(${library_name} - ${dependencies} + src/nav2_rotation_shim_controller.cpp) +target_include_directories(${library_name} + PUBLIC + "$" + "$" +) +target_link_libraries(${library_name} PUBLIC + ${geometry_msgs_TARGETS} + nav2_core::nav2_core + nav2_costmap_2d::nav2_costmap_2d_core + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + ${rcl_interfaces_TARGETS} + tf2_ros::tf2_ros +) +target_link_libraries(${library_name} PRIVATE + angles::angles + nav2_util::nav2_util_core + tf2::tf2 ) install(TARGETS ${library_name} + EXPORT ${library_name} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin ) install(DIRECTORY include/ - DESTINATION include/ + DESTINATION include/${PROJECT_NAME} ) if(BUILD_TESTING) @@ -56,12 +59,24 @@ if(BUILD_TESTING) # the following line skips the linter which checks for copyrights set(ament_cmake_copyright_FOUND TRUE) ament_lint_auto_find_test_dependencies() + + ament_find_gtest() add_subdirectory(test) endif() -ament_export_include_directories(include) +ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(${library_name}) -ament_export_dependencies(${dependencies}) +ament_export_dependencies( + geometry_msgs + nav2_core + nav2_costmap_2d + pluginlib + rclcpp + rclcpp_lifecycle + rcl_interfaces + tf2_ros +) +ament_export_targets(${library_name}) pluginlib_export_plugin_description_file(nav2_core nav2_rotation_shim_controller.xml) diff --git a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp index 6d4e8b86b3..f0da5e0fba 100644 --- a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp +++ b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp @@ -24,13 +24,9 @@ #include "rclcpp/rclcpp.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/geometry_utils.hpp" -#include "nav2_util/robot_utils.hpp" #include "nav2_core/controller.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "nav2_util/node_utils.hpp" #include "nav2_costmap_2d/footprint_collision_checker.hpp" -#include "angles/angles.h" namespace nav2_rotation_shim_controller { diff --git a/nav2_rotation_shim_controller/package.xml b/nav2_rotation_shim_controller/package.xml index 1fadbbe2c5..9e450f7573 100644 --- a/nav2_rotation_shim_controller/package.xml +++ b/nav2_rotation_shim_controller/package.xml @@ -8,17 +8,20 @@ Apache-2.0 ament_cmake + nav2_common - nav2_common + angles + geometry_msgs nav2_core - nav2_util nav2_costmap_2d - rclcpp - geometry_msgs nav2_msgs - angles + nav2_util pluginlib + rclcpp + rclcpp_lifecycle + rcl_interfaces tf2 + tf2_ros ament_cmake_gtest ament_lint_common diff --git a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp index afb74c357e..4e111edfda 100644 --- a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp +++ b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp @@ -18,6 +18,11 @@ #include #include +#include "angles/angles.h" +#include "nav2_util/geometry_utils.hpp" +#include "nav2_util/node_utils.hpp" +#include "nav2_util/robot_utils.hpp" + #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp" #include "nav2_rotation_shim_controller/tools/utils.hpp" diff --git a/nav2_rotation_shim_controller/test/CMakeLists.txt b/nav2_rotation_shim_controller/test/CMakeLists.txt index ae3161d1a7..e2d79806a3 100644 --- a/nav2_rotation_shim_controller/test/CMakeLists.txt +++ b/nav2_rotation_shim_controller/test/CMakeLists.txt @@ -4,10 +4,11 @@ find_package(nav2_controller REQUIRED) ament_add_gtest(test_shim_controller test_shim_controller.cpp ) -ament_target_dependencies(test_shim_controller - ${dependencies} - nav2_controller -) target_link_libraries(test_shim_controller ${library_name} + rclcpp::rclcpp + nav2_costmap_2d::nav2_costmap_2d_core + nav2_controller::simple_goal_checker + nav2_util::nav2_util_core + tf2_ros::tf2_ros )