Skip to content

Commit

Permalink
Switch nav2_smoother to modern CMake idioms. (ros-navigation#4603)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
Signed-off-by: Joseph Duchesne <[email protected]>
  • Loading branch information
clalancette authored and josephduchesne committed Dec 10, 2024
1 parent 1e962b1 commit 3a0f160
Show file tree
Hide file tree
Showing 3 changed files with 132 additions and 77 deletions.
144 changes: 92 additions & 52 deletions nav2_smoother/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,79 +2,108 @@ cmake_minimum_required(VERSION 3.5)
project(nav2_smoother)

find_package(ament_cmake REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_common REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_2d_utils REQUIRED)
find_package(nav_2d_msgs REQUIRED)
find_package(pluginlib REQUIRED)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)

nav2_package()

include_directories(
include
)

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

set(dependencies
angles
rclcpp
rclcpp_components
rclcpp_action
rclcpp_components
std_msgs
nav2_msgs
nav_2d_utils
nav_2d_msgs
nav2_util
nav2_core
pluginlib
)

# Main library
add_library(${library_name} SHARED
src/nav2_smoother.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} PUBLIC
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)
target_link_libraries(${library_name} PRIVATE
nav_2d_utils::conversions
nav_2d_utils::tf_help
rclcpp_components::component
tf2::tf2
)

# Main executable
add_executable(${executable_name}
src/main.cpp
)
ament_target_dependencies(${executable_name}
${dependencies}
)
target_link_libraries(${executable_name} ${library_name})
target_include_directories(${executable_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(${executable_name} PRIVATE rclcpp::rclcpp ${library_name})

# Simple Smoother plugin
add_library(simple_smoother SHARED
src/simple_smoother.cpp
)
ament_target_dependencies(simple_smoother
${dependencies}
target_include_directories(simple_smoother
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(simple_smoother PUBLIC
angles::angles
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(simple_smoother PRIVATE
pluginlib::pluginlib
)

# Savitzky Golay Smoother plugin
add_library(savitzky_golay_smoother SHARED
src/savitzky_golay_smoother.cpp
)
ament_target_dependencies(savitzky_golay_smoother
${dependencies}
target_include_directories(savitzky_golay_smoother
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(savitzky_golay_smoother PUBLIC
angles::angles
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(savitzky_golay_smoother PRIVATE
pluginlib::pluginlib
)

pluginlib_export_plugin_description_file(nav2_core plugins.xml)
Expand All @@ -87,12 +116,18 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rclcpp_action REQUIRED)

ament_find_gtest()
add_subdirectory(test)
endif()

rclcpp_components_register_nodes(${library_name} "nav2_smoother::SmootherServer")

install(
TARGETS ${library_name} simple_smoother savitzky_golay_smoother
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -103,17 +138,22 @@ install(TARGETS ${executable_name}
)

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

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_gtest REQUIRED)
add_subdirectory(test)
endif()

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(${library_name} simple_smoother savitzky_golay_smoother)
ament_export_dependencies(${dependencies})
ament_export_dependencies(
angles
nav2_core
nav2_costmap_2d
nav2_msgs
nav2_util
pluginlib
rclcpp
rclcpp_lifecycle
tf2
tf2_ros
)
ament_export_targets(${library_name})
ament_package()
21 changes: 12 additions & 9 deletions nav2_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,22 +10,25 @@

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

<depend>angles</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_action</depend>
<depend>std_msgs</depend>
<depend>nav2_util</depend>
<depend>nav2_core</depend>
<depend>nav2_costmap_2d</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>nav_2d_utils</depend>
<depend>nav_2d_msgs</depend>
<depend>nav2_core</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_index_cpp</test_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>
<test_depend>rclcpp_action</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
44 changes: 28 additions & 16 deletions nav2_smoother/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,36 +1,48 @@
ament_add_gtest(test_smoother_server
test_smoother_server.cpp
)

target_link_libraries(test_smoother_server
${library_name}
)

ament_target_dependencies(test_smoother_server
${dependencies}
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_action::rclcpp_action
rclcpp_lifecycle::rclcpp_lifecycle
)

ament_add_gtest(test_simple_smoother
test_simple_smoother.cpp
)

target_link_libraries(test_simple_smoother
simple_smoother
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
)

ament_target_dependencies(test_simple_smoother
${dependencies}
)


ament_add_gtest(test_savitzky_golay_smoother
test_savitzky_golay_smoother.cpp
)

target_link_libraries(test_savitzky_golay_smoother
savitzky_golay_smoother
)

ament_target_dependencies(test_savitzky_golay_smoother
${dependencies}
ament_index_cpp::ament_index_cpp
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)

0 comments on commit 3a0f160

Please sign in to comment.