Skip to content

Commit

Permalink
Switch opennav_docking to modern CMake idioms. (#4633)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 20, 2024
1 parent 24a28d7 commit 2e824e9
Show file tree
Hide file tree
Showing 5 changed files with 156 additions and 100 deletions.
163 changes: 100 additions & 63 deletions nav2_docking/opennav_docking/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,113 +3,133 @@ project(opennav_docking)

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_graceful_controller REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(opennav_docking_core REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(pluginlib REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(yaml-cpp REQUIRED)
find_package(opennav_docking_core REQUIRED)

# potentially replace with nav2_common, nav2_package()
set(CMAKE_CXX_STANDARD 17)
add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow -Wnull-dereference)

include_directories(
include
)
nav2_package()

set(executable_name opennav_docking)
set(library_name ${executable_name}_core)

set(dependencies
angles
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
sensor_msgs
visualization_msgs
nav2_graceful_controller
nav2_util
nav2_msgs
nav_msgs
geometry_msgs
builtin_interfaces
tf2_ros
tf2_geometry_msgs
pluginlib
yaml_cpp_vendor
opennav_docking_core
)

add_library(controller SHARED
src/controller.cpp
)

ament_target_dependencies(controller
${dependencies}
target_include_directories(controller
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(controller PUBLIC
${geometry_msgs_TARGETS}
nav2_graceful_controller::nav2_graceful_controller
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
)

add_library(${library_name} SHARED
src/docking_server.cpp
src/dock_database.cpp
src/navigator.cpp
)

ament_target_dependencies(${library_name}
${dependencies}
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

target_link_libraries(${library_name}
yaml-cpp::yaml-cpp
target_link_libraries(${library_name} PUBLIC
angles::angles
controller
${geometry_msgs_TARGETS}
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
opennav_docking_core::opennav_docking_core
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_action::rclcpp_action
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
tf2_ros::tf2_ros
yaml-cpp::yaml-cpp
)
target_link_libraries(${library_name} PRIVATE
rclcpp_components::component
tf2_geometry_msgs::tf2_geometry_msgs
)

add_library(pose_filter SHARED
src/pose_filter.cpp
)

ament_target_dependencies(pose_filter
${dependencies}
target_include_directories(pose_filter
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(pose_filter PUBLIC
${geometry_msgs_TARGETS}
)
target_link_libraries(pose_filter PRIVATE
rclcpp::rclcpp
tf2_geometry_msgs::tf2_geometry_msgs
)

add_executable(${executable_name}
src/main.cpp
)

target_link_libraries(${executable_name} ${library_name})

ament_target_dependencies(${executable_name}
${dependencies}
target_include_directories(${executable_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(${executable_name} PRIVATE ${library_name} rclcpp::rclcpp)

rclcpp_components_register_nodes(${library_name} "opennav_docking::DockingServer")

add_library(simple_charging_dock SHARED
src/simple_charging_dock.cpp
)
ament_target_dependencies(simple_charging_dock
${dependencies}
target_include_directories(simple_charging_dock
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(simple_charging_dock PUBLIC
${geometry_msgs_TARGETS}
opennav_docking_core::opennav_docking_core
pose_filter
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${sensor_msgs_TARGETS}
tf2_geometry_msgs::tf2_geometry_msgs
tf2_ros::tf2_ros
)
target_link_libraries(simple_charging_dock PRIVATE
nav2_util::nav2_util_core
pluginlib::pluginlib
tf2::tf2
)
target_link_libraries(simple_charging_dock pose_filter)

pluginlib_export_plugin_description_file(opennav_docking_core plugins.xml)

install(TARGETS ${library_name} controller pose_filter simple_charging_dock
EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -120,7 +140,7 @@ install(TARGETS ${executable_name}
)

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

install(FILES test/test_dock_file.yaml
Expand All @@ -131,11 +151,28 @@ if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)
find_package(ament_index_cpp REQUIRED)

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} controller pose_filter)
ament_export_dependencies(${dependencies} yaml-cpp)
ament_export_dependencies(
geometry_msgs
nav2_graceful_controller
nav2_msgs
nav2_util
opennav_docking_core
pluginlib
rclcpp
rclcpp_action
rclcpp_lifecycle
rcl_interfaces
tf2_ros
yaml-cpp
)
ament_export_targets(${PROJECT_NAME})
ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define OPENNAV_DOCKING__POSE_FILTER_HPP_

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace opennav_docking
{
Expand Down
21 changes: 13 additions & 8 deletions nav2_docking/opennav_docking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,25 +8,30 @@
<license>Apache-2.0</license>

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

<depend>angles</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_lifecycle</depend>
<depend>geometry_msgs</depend>
<depend>nav2_graceful_controller</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>nav_msgs</depend>
<depend>geometry_msgs</depend>
<depend>builtin_interfaces</depend>
<depend>sensor_msgs</depend>
<depend>pluginlib</depend>
<depend>yaml_cpp_vendor</depend>
<depend>opennav_docking_core</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rcl_interfaces</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>yaml_cpp_vendor</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_common</test_depend>
<test_depend>ament_lint_auto</test_depend>

Expand Down
1 change: 1 addition & 0 deletions nav2_docking/opennav_docking/src/pose_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "opennav_docking/pose_filter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace opennav_docking
{
Expand Down
Loading

0 comments on commit 2e824e9

Please sign in to comment.