Skip to content

Commit

Permalink
Update nav2_behaviors to use 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 Jul 30, 2024
1 parent a001bfc commit ce2e6b6
Show file tree
Hide file tree
Showing 3 changed files with 159 additions and 95 deletions.
210 changes: 144 additions & 66 deletions nav2_behaviors/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,89 +2,140 @@ cmake_minimum_required(VERSION 3.5)
project(nav2_behaviors)

find_package(ament_cmake 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_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(nav2_core REQUIRED)
find_package(pluginlib REQUIRED)
find_package(tf2_ros REQUIRED)

nav2_package()

include_directories(
include
)

set(library_name behavior_server_core)
set(executable_name behavior_server)

set(dependencies
rclcpp
rclcpp_action
rclcpp_lifecycle
rclcpp_components
std_msgs
nav2_util
nav2_behavior_tree
nav2_msgs
nav_msgs
tf2
tf2_geometry_msgs
geometry_msgs
nav2_costmap_2d
nav2_core
pluginlib
)

# plugins
add_library(nav2_spin_behavior SHARED
plugins/spin.cpp
)

ament_target_dependencies(nav2_spin_behavior
${dependencies}
target_include_directories(nav2_spin_behavior
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(nav2_spin_behavior PUBLIC
${geometry_msgs_TARGETS}
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
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(nav2_spin_behavior PRIVATE
pluginlib::pluginlib
tf2_geometry_msgs::tf2_geometry_msgs
)

add_library(nav2_wait_behavior SHARED
plugins/wait.cpp
plugins/wait.cpp
)

ament_target_dependencies(nav2_wait_behavior
${dependencies}
target_include_directories(nav2_wait_behavior
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(nav2_wait_behavior PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)

add_library(nav2_drive_on_heading_behavior SHARED
plugins/drive_on_heading.cpp
)

ament_target_dependencies(nav2_drive_on_heading_behavior
${dependencies}
target_include_directories(nav2_drive_on_heading_behavior
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(nav2_drive_on_heading_behavior PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(nav2_drive_on_heading_behavior PRIVATE
pluginlib::pluginlib
)

add_library(nav2_back_up_behavior SHARED
plugins/back_up.cpp
)

ament_target_dependencies(nav2_back_up_behavior
${dependencies}
target_include_directories(nav2_back_up_behavior
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(nav2_back_up_behavior PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(nav2_back_up_behavior PRIVATE
pluginlib::pluginlib
)

add_library(nav2_assisted_teleop_behavior SHARED
plugins/assisted_teleop.cpp
)

ament_target_dependencies(nav2_assisted_teleop_behavior
${dependencies}
target_include_directories(nav2_assisted_teleop_behavior
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(nav2_assisted_teleop_behavior PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
${nav2_msgs_TARGETS}
nav2_util::nav2_util_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${std_msgs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
)
target_link_libraries(nav2_assisted_teleop_behavior PRIVATE
pluginlib::pluginlib
)

pluginlib_export_plugin_description_file(nav2_core behavior_plugin.xml)
Expand All @@ -93,30 +144,41 @@ pluginlib_export_plugin_description_file(nav2_core behavior_plugin.xml)
add_library(${library_name} SHARED
src/behavior_server.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_util::nav2_util_core
pluginlib::pluginlib
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)
target_link_libraries(${library_name} PRIVATE
rclcpp_components::component
)

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

target_link_libraries(${executable_name} ${library_name})

ament_target_dependencies(${executable_name}
${dependencies}
)
target_link_libraries(${executable_name} PRIVATE rclcpp::rclcpp ${library_name})

rclcpp_components_register_nodes(${library_name} "behavior_server::BehaviorServer")

install(TARGETS ${library_name}
nav2_spin_behavior
nav2_wait_behavior
nav2_assisted_teleop_behavior
nav2_drive_on_heading_behavior
nav2_back_up_behavior
install(
TARGETS
${library_name}
nav2_spin_behavior
nav2_wait_behavior
nav2_assisted_teleop_behavior
nav2_drive_on_heading_behavior
nav2_back_up_behavior
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -127,7 +189,7 @@ install(TARGETS ${executable_name}
)

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

install(FILES behavior_plugin.xml
Expand All @@ -142,16 +204,32 @@ if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_gtest REQUIRED)
find_package(rclcpp_action REQUIRED)

ament_find_gtest()
add_subdirectory(test)
endif()

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(${library_name}
nav2_spin_behavior
nav2_wait_behavior
nav2_assisted_teleop_behavior
nav2_drive_on_heading_behavior
nav2_back_up_behavior
)
ament_export_dependencies(${dependencies})
ament_export_dependencies(
geometry_msgs
nav2_core
nav2_costmap_2d
nav2_msgs
nav2_util
pluginlib
rclcpp
rclcpp_lifecycle
std_msgs
tf2
tf2_ros
)
ament_export_targets(${library_name})
ament_package()
39 changes: 14 additions & 25 deletions nav2_behaviors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,35 +11,24 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_action</build_depend>
<build_depend>rclcpp_lifecycle</build_depend>
<build_depend>nav2_behavior_tree</build_depend>
<build_depend>nav2_util</build_depend>
<build_depend>nav2_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>tf2</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>nav2_costmap_2d</build_depend>
<build_depend>nav2_core</build_depend>
<build_depend>pluginlib</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_action</exec_depend>
<exec_depend>rclcpp_lifecycle</exec_depend>
<exec_depend>nav2_behavior_tree</exec_depend>
<exec_depend>nav2_util</exec_depend>
<exec_depend>nav2_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>nav2_costmap_2d</exec_depend>
<exec_depend>nav2_core</exec_depend>
<exec_depend>pluginlib</exec_depend>
<depend>geometry_msgs</depend>
<depend>nav2_core</depend>
<depend>nav2_costmap_2d</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_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>rclcpp_action</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
5 changes: 1 addition & 4 deletions nav2_behaviors/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,4 @@
ament_add_gtest(test_behaviors
test_behaviors.cpp
)

ament_target_dependencies(test_behaviors
${dependencies}
)
target_link_libraries(test_behaviors rclcpp::rclcpp rclcpp_action::rclcpp_action ${nav2_msgs_TARGETS} ${library_name})

0 comments on commit ce2e6b6

Please sign in to comment.