Skip to content

Commit

Permalink
Switch nav2_controller to modern CMake idioms. (#4586)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 1, 2024
1 parent 6751457 commit 495fe89
Show file tree
Hide file tree
Showing 4 changed files with 153 additions and 63 deletions.
189 changes: 137 additions & 52 deletions nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,67 +2,146 @@ cmake_minimum_required(VERSION 3.5)
project(nav2_controller)

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_common REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav_2d_utils REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_2d_msgs REQUIRED)
find_package(nav_2d_utils REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(tf2_ros REQUIRED)

nav2_package()

include_directories(
include
)

set(executable_name controller_server)

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

set(library_name ${executable_name}_core)

add_library(${library_name} SHARED
src/controller_server.cpp
)
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(${library_name} PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
${nav_2d_msgs_TARGETS}
nav_2d_utils::conversions
nav_2d_utils::tf_help
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
tf2_ros::tf2_ros
)
target_link_libraries(${library_name} PRIVATE
${lifecycle_msgs_TARGETS}
rclcpp_components::component
)

set(dependencies
angles
rclcpp
rclcpp_action
rclcpp_components
std_msgs
nav2_msgs
nav_2d_utils
nav_2d_msgs
nav2_util
nav2_core
pluginlib
add_executable(${executable_name}
src/main.cpp
)
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}
)

add_library(simple_progress_checker SHARED plugins/simple_progress_checker.cpp)
ament_target_dependencies(simple_progress_checker ${dependencies})
target_include_directories(simple_progress_checker
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(simple_progress_checker PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
)
target_link_libraries(simple_progress_checker PRIVATE
nav2_util::nav2_util_core
nav_2d_utils::conversions
pluginlib::pluginlib
)

add_library(pose_progress_checker SHARED plugins/pose_progress_checker.cpp)
target_link_libraries(pose_progress_checker simple_progress_checker)
ament_target_dependencies(pose_progress_checker ${dependencies})
target_include_directories(pose_progress_checker
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(pose_progress_checker PUBLIC
${geometry_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
simple_progress_checker
)
target_link_libraries(pose_progress_checker PRIVATE
angles::angles
nav2_util::nav2_util_core
nav_2d_utils::conversions
pluginlib::pluginlib
)

add_library(simple_goal_checker SHARED plugins/simple_goal_checker.cpp)
ament_target_dependencies(simple_goal_checker ${dependencies})
target_include_directories(simple_goal_checker
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(simple_goal_checker PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
)
target_link_libraries(simple_goal_checker PRIVATE
angles::angles
nav2_util::nav2_util_core
pluginlib::pluginlib
tf2::tf2
)

add_library(stopped_goal_checker SHARED plugins/stopped_goal_checker.cpp)
target_link_libraries(stopped_goal_checker simple_goal_checker)
ament_target_dependencies(stopped_goal_checker ${dependencies})

ament_target_dependencies(${library_name}
${dependencies}
target_include_directories(stopped_goal_checker
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(stopped_goal_checker PUBLIC
${geometry_msgs_TARGETS}
nav2_costmap_2d::nav2_costmap_2d_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
simple_goal_checker
)
target_link_libraries(stopped_goal_checker PRIVATE
nav2_util::nav2_util_core
pluginlib::pluginlib
)

if(BUILD_TESTING)
Expand All @@ -72,18 +151,17 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
add_subdirectory(plugins/test)
endif()

ament_target_dependencies(${executable_name}
${dependencies}
)
ament_find_gtest()

target_link_libraries(${executable_name} ${library_name})
add_subdirectory(test)
add_subdirectory(plugins/test)
endif()

rclcpp_components_register_nodes(${library_name} "nav2_controller::ControllerServer")

install(TARGETS simple_progress_checker pose_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -94,23 +172,30 @@ install(TARGETS ${executable_name}
)

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

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

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(simple_progress_checker
pose_progress_checker
simple_goal_checker
stopped_goal_checker
${library_name})
ament_export_dependencies(${dependencies})
ament_export_dependencies(
geometry_msgs
nav2_core
nav2_costmap_2d
nav2_msgs
nav2_util
nav_2d_msgs
nav_2d_utils
pluginlib
rclcpp
rclcpp_lifecycle
rcl_interfaces
tf2_ros
)
ament_export_targets(${library_name})
pluginlib_export_plugin_description_file(nav2_core plugins.xml)

ament_package()
17 changes: 11 additions & 6 deletions nav2_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,16 +9,21 @@

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

<depend>angles</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>std_msgs</depend>
<depend>nav2_util</depend>
<depend>geometry_msgs</depend>
<depend>lifecycle_msgs</depend>
<depend>nav2_core</depend>
<depend>nav2_msgs</depend>
<depend>nav_2d_utils</depend>
<depend>nav2_util</depend>
<depend>nav_2d_msgs</depend>
<depend>nav2_core</depend>
<depend>nav_2d_utils</depend>
<depend>pluginlib</depend>
<depend>rcl_interfaces</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>tf2_ros</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
5 changes: 3 additions & 2 deletions nav2_controller/plugins/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
ament_add_gtest(pctest progress_checker.cpp)
target_link_libraries(pctest simple_progress_checker pose_progress_checker)
target_link_libraries(pctest simple_progress_checker pose_progress_checker nav_2d_utils::conversions)

ament_add_gtest(gctest goal_checker.cpp)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker nav_2d_utils::conversions)
5 changes: 2 additions & 3 deletions nav2_controller/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,8 @@
ament_add_gtest(test_dynamic_parameters
test_dynamic_parameters.cpp
)
ament_target_dependencies(test_dynamic_parameters
${dependencies}
)
target_link_libraries(test_dynamic_parameters
${library_name}
nav2_util::nav2_util_core
rclcpp::rclcpp
)

0 comments on commit 495fe89

Please sign in to comment.