Skip to content

Commit

Permalink
Switch dwb_core to modern CMake idioms. (ros-navigation#4610)
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 240a29e commit c9878ca
Show file tree
Hide file tree
Showing 3 changed files with 76 additions and 67 deletions.
93 changes: 56 additions & 37 deletions nav2_dwb_controller/dwb_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,64 +2,64 @@ cmake_minimum_required(VERSION 3.5)
project(dwb_core)

find_package(ament_cmake REQUIRED)
find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav_2d_msgs REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(dwb_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(pluginlib REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav_2d_msgs REQUIRED)
find_package(nav_2d_utils REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_core REQUIRED)
find_package(visualization_msgs REQUIRED)

nav2_package()

include_directories(
include
)

set(dependencies
rclcpp
std_msgs
geometry_msgs
nav_2d_msgs
dwb_msgs
nav2_costmap_2d
pluginlib
sensor_msgs
visualization_msgs
nav_2d_utils
nav_msgs
tf2_ros
nav2_util
nav2_core
)

add_library(dwb_core SHARED
src/dwb_local_planner.cpp
src/publisher.cpp
src/illegal_trajectory_tracker.cpp
src/trajectory_utils.cpp
)

ament_target_dependencies(dwb_core
${dependencies}
target_include_directories(dwb_core PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(dwb_core PUBLIC
${builtin_interfaces_TARGETS}
${dwb_msgs_TARGETS}
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
${nav_2d_msgs_TARGETS}
nav_2d_utils::conversions
nav_2d_utils::tf_help
${nav_msgs_TARGETS}
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${sensor_msgs_TARGETS}
tf2_ros::tf2_ros
${visualization_msgs_TARGETS}
)

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

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

if(BUILD_TESTING)
Expand All @@ -69,12 +69,31 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
ament_find_gtest()

add_subdirectory(test)
endif()

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(dwb_core)
ament_export_dependencies(${dependencies})
ament_export_dependencies(
builtin_interfaces
dwb_msgs
geometry_msgs
nav2_core
nav2_costmap_2d
nav2_util
nav_2d_msgs
nav_2d_utils
nav_msgs
pluginlib
rclcpp
rclcpp_lifecycle
sensor_msgs
tf2_ros
visualization_msgs
)
ament_export_targets(dwb_core)

pluginlib_export_plugin_description_file(nav2_core local_planner_plugin.xml)

Expand Down
45 changes: 16 additions & 29 deletions nav2_dwb_controller/dwb_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,38 +10,25 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>nav_2d_msgs</build_depend>
<build_depend>dwb_msgs</build_depend>
<build_depend>nav2_costmap_2d</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>visualization_msgs</build_depend>
<build_depend>nav_2d_utils</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>tf2_ros</build_depend>
<build_depend>nav2_util</build_depend>
<build_depend>nav2_core</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>dwb_msgs</exec_depend>
<exec_depend>nav2_costmap_2d</exec_depend>
<exec_depend>nav_2d_utils</exec_depend>
<exec_depend>pluginlib</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>nav2_util</exec_depend>
<exec_depend>nav2_core</exec_depend>
<depend>builtin_interfaces</depend>
<depend>dwb_msgs</depend>
<depend>geometry_msgs</depend>
<depend>nav2_core</depend>
<depend>nav2_costmap_2d</depend>
<depend>nav2_util</depend>
<depend>nav_2d_msgs</depend>
<depend>nav_2d_utils</depend>
<depend>nav_msgs</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>sensor_msgs</depend>
<depend>tf2_ros</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_gtest</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
5 changes: 4 additions & 1 deletion nav2_dwb_controller/dwb_core/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1,5 @@
ament_add_gtest(utils_test utils_test.cpp)
target_link_libraries(utils_test dwb_core)
target_link_libraries(utils_test
dwb_core
${dwb_msgs_TARGETS}
)

0 comments on commit c9878ca

Please sign in to comment.