Skip to content

Commit

Permalink
Switch opennav_docking_core to modern CMake idioms.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Aug 20, 2024
1 parent fe639ed commit 8a9ef29
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 18 deletions.
38 changes: 27 additions & 11 deletions nav2_docking/opennav_docking_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,23 +2,34 @@ cmake_minimum_required(VERSION 3.5)
project(opennav_docking_core)

find_package(ament_cmake REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(tf2_ros REQUIRED)

nav2_package()

set(dependencies
rclcpp
rclcpp_lifecycle
nav2_msgs
nav2_util
add_library(opennav_docking_core INTERFACE)
target_include_directories(opennav_docking_core
INTERFACE
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(opennav_docking_core INTERFACE
${geometry_msgs_TARGETS}
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)

install(TARGETS opennav_docking_core
EXPORT opennav_docking_core
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(DIRECTORY include/
DESTINATION include/
DESTINATION include/${PROJECT_NAME}
)

if(BUILD_TESTING)
Expand All @@ -28,7 +39,12 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_include_directories(include)
ament_export_dependencies(${dependencies})
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_dependencies(
geometry_msgs
rclcpp_lifecycle
tf2_ros
)
ament_export_targets(opennav_docking_core)

ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,8 @@
#include <string>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "tf2_ros/buffer.h"


Expand Down
8 changes: 3 additions & 5 deletions nav2_docking/opennav_docking_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,14 @@
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp_lifecycle</depend>
<depend>nav2_util</depend>
<depend>nav2_msgs</depend>
<depend>tf2_ros</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>

<export>
<build_type>ament_cmake</build_type>
Expand Down

0 comments on commit 8a9ef29

Please sign in to comment.