Skip to content

Commit 9c7ec08

Browse files
clalancettestevedanomodolor
authored andcommitted
Switch nav2_waypoint_follower to modern CMake idioms. (ros-navigation#4648)
Signed-off-by: Chris Lalancette <[email protected]> Signed-off-by: stevedanomodolor <[email protected]>
1 parent d95129c commit 9c7ec08

File tree

4 files changed

+141
-81
lines changed

4 files changed

+141
-81
lines changed
Lines changed: 114 additions & 54 deletions
Original file line numberDiff line numberDiff line change
@@ -1,87 +1,126 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(nav2_waypoint_follower)
33

4-
# Try for OpenCV 4.X, but settle for whatever is installed
5-
find_package(OpenCV 4 QUIET)
6-
if(NOT OpenCV_FOUND)
7-
find_package(OpenCV REQUIRED)
8-
endif()
9-
message(STATUS "Found OpenCV version ${OpenCV_VERSION}")
10-
11-
find_package(image_transport REQUIRED)
12-
find_package(cv_bridge REQUIRED)
134
find_package(ament_cmake REQUIRED)
5+
find_package(cv_bridge REQUIRED)
6+
find_package(geographic_msgs REQUIRED)
7+
find_package(geometry_msgs REQUIRED)
8+
find_package(image_transport REQUIRED)
149
find_package(nav2_common REQUIRED)
15-
find_package(rclcpp REQUIRED)
16-
find_package(rclcpp_action REQUIRED)
17-
find_package(rclcpp_lifecycle REQUIRED)
18-
find_package(rclcpp_components REQUIRED)
19-
find_package(nav_msgs REQUIRED)
10+
find_package(nav2_core REQUIRED)
2011
find_package(nav2_msgs REQUIRED)
2112
find_package(nav2_util REQUIRED)
22-
find_package(tf2_ros REQUIRED)
23-
find_package(nav2_core REQUIRED)
13+
find_package(nav_msgs REQUIRED)
14+
find_package(OpenCV REQUIRED)
2415
find_package(pluginlib REQUIRED)
16+
find_package(rclcpp REQUIRED)
17+
find_package(rclcpp_action REQUIRED)
18+
find_package(rclcpp_components REQUIRED)
19+
find_package(rclcpp_lifecycle REQUIRED)
2520
find_package(robot_localization REQUIRED)
26-
find_package(geographic_msgs REQUIRED)
21+
find_package(sensor_msgs REQUIRED)
22+
find_package(std_msgs REQUIRED)
23+
find_package(tf2_ros REQUIRED)
2724

2825
nav2_package()
2926

30-
include_directories(
31-
include
32-
)
33-
3427
set(executable_name waypoint_follower)
3528

36-
add_executable(${executable_name}
37-
src/main.cpp
38-
)
39-
4029
set(library_name ${executable_name}_core)
4130

4231
add_library(${library_name} SHARED
4332
src/waypoint_follower.cpp
4433
)
45-
46-
set(dependencies
47-
rclcpp
48-
rclcpp_action
49-
rclcpp_lifecycle
50-
rclcpp_components
51-
nav_msgs
52-
nav2_msgs
53-
nav2_util
54-
tf2_ros
55-
nav2_core
56-
pluginlib
57-
image_transport
58-
cv_bridge
59-
OpenCV
60-
robot_localization
34+
target_include_directories(${library_name} PUBLIC
35+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
36+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
6137
)
62-
63-
ament_target_dependencies(${executable_name}
64-
${dependencies}
38+
target_link_libraries(${library_name} PUBLIC
39+
${geographic_msgs_TARGETS}
40+
nav2_core::nav2_core
41+
${nav2_msgs_TARGETS}
42+
nav2_util::nav2_util_core
43+
${nav_msgs_TARGETS}
44+
pluginlib::pluginlib
45+
rclcpp::rclcpp
46+
rclcpp_action::rclcpp_action
47+
rclcpp_lifecycle::rclcpp_lifecycle
48+
robot_localization::rl_lib
49+
tf2_ros::tf2_ros
50+
)
51+
target_link_libraries(${library_name} PRIVATE
52+
rclcpp_components::component
6553
)
6654

67-
target_link_libraries(${executable_name} ${library_name})
68-
69-
ament_target_dependencies(${library_name}
70-
${dependencies}
55+
add_executable(${executable_name}
56+
src/main.cpp
57+
)
58+
target_include_directories(${executable_name} PRIVATE
59+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
60+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
61+
)
62+
target_link_libraries(${executable_name} PRIVATE
63+
${library_name}
64+
rclcpp::rclcpp
7165
)
7266

7367
add_library(wait_at_waypoint SHARED plugins/wait_at_waypoint.cpp)
74-
ament_target_dependencies(wait_at_waypoint ${dependencies})
68+
target_include_directories(wait_at_waypoint PUBLIC
69+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
70+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
71+
)
72+
target_link_libraries(wait_at_waypoint PUBLIC
73+
${geometry_msgs_TARGETS}
74+
rclcpp::rclcpp
75+
rclcpp_lifecycle::rclcpp_lifecycle
76+
nav2_core::nav2_core
77+
)
78+
target_link_libraries(wait_at_waypoint PRIVATE
79+
pluginlib::pluginlib
80+
nav2_util::nav2_util_core
81+
)
7582

7683
add_library(photo_at_waypoint SHARED plugins/photo_at_waypoint.cpp)
77-
ament_target_dependencies(photo_at_waypoint ${dependencies})
84+
target_include_directories(photo_at_waypoint PUBLIC
85+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
86+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
87+
)
88+
target_link_libraries(photo_at_waypoint PUBLIC
89+
cv_bridge::cv_bridge
90+
${geometry_msgs_TARGETS}
91+
image_transport::image_transport
92+
nav2_core::nav2_core
93+
opencv_core
94+
rclcpp::rclcpp
95+
rclcpp_lifecycle::rclcpp_lifecycle
96+
${sensor_msgs_TARGETS}
97+
)
98+
target_link_libraries(photo_at_waypoint PRIVATE
99+
nav2_util::nav2_util_core
100+
pluginlib::pluginlib
101+
)
78102

79103
add_library(input_at_waypoint SHARED plugins/input_at_waypoint.cpp)
80-
ament_target_dependencies(input_at_waypoint ${dependencies})
104+
target_include_directories(input_at_waypoint PUBLIC
105+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
106+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
107+
)
108+
target_link_libraries(input_at_waypoint PUBLIC
109+
${geometry_msgs_TARGETS}
110+
nav2_core::nav2_core
111+
rclcpp::rclcpp
112+
rclcpp_lifecycle::rclcpp_lifecycle
113+
${std_msgs_TARGETS}
114+
)
115+
target_link_libraries(input_at_waypoint PRIVATE
116+
pluginlib::pluginlib
117+
nav2_util::nav2_util_core
118+
)
81119

82120
rclcpp_components_register_nodes(${library_name} "nav2_waypoint_follower::WaypointFollower")
83121

84122
install(TARGETS ${library_name} wait_at_waypoint photo_at_waypoint input_at_waypoint
123+
EXPORT ${PROJECT_NAME}
85124
ARCHIVE DESTINATION lib
86125
LIBRARY DESTINATION lib
87126
RUNTIME DESTINATION bin
@@ -92,19 +131,40 @@ install(TARGETS ${executable_name}
92131
)
93132

94133
install(DIRECTORY include/
95-
DESTINATION include/
134+
DESTINATION include/${PROJECT_NAME}
96135
)
97136

98137
if(BUILD_TESTING)
99138
find_package(ament_lint_auto REQUIRED)
100139
find_package(ament_cmake_gtest REQUIRED)
101140
ament_lint_auto_find_test_dependencies()
141+
142+
ament_find_gtest()
102143
add_subdirectory(test)
103144
endif()
104145

105-
ament_export_include_directories(include)
146+
ament_export_include_directories(include/${PROJECT_NAME})
106147
ament_export_libraries(wait_at_waypoint photo_at_waypoint input_at_waypoint ${library_name})
107-
ament_export_dependencies(${dependencies})
148+
ament_export_dependencies(
149+
cv_bridge
150+
geographic_msgs
151+
geometry_msgs
152+
image_transport
153+
nav2_core
154+
nav2_msgs
155+
nav2_util
156+
nav_msgs
157+
OpenCV
158+
pluginlib
159+
rclcpp
160+
rclcpp_action
161+
rclcpp_lifecycle
162+
robot_localization
163+
sensor_msgs
164+
std_msgs
165+
tf2_ros
166+
)
167+
ament_export_targets(${PROJECT_NAME})
108168
pluginlib_export_plugin_description_file(nav2_waypoint_follower plugins.xml)
109169

110170
ament_package()

nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -15,20 +15,12 @@
1515
#ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
1616
#define NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
1717

18-
/**
19-
* While C++17 isn't the project standard. We have to force LLVM/CLang
20-
* to ignore deprecated declarations
21-
*/
22-
#define _LIBCPP_NO_EXPERIMENTAL_DEPRECATION_WARNING_FILESYSTEM
23-
24-
2518
#include <filesystem>
2619
#include <mutex>
2720
#include <string>
2821
#include <exception>
2922

3023
#include "rclcpp/rclcpp.hpp"
31-
#include "rclcpp_components/register_node_macro.hpp"
3224

3325
#include "sensor_msgs/msg/image.hpp"
3426
#include "nav2_core/waypoint_task_executor.hpp"

nav2_waypoint_follower/package.xml

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -8,26 +8,29 @@
88
<license>Apache-2.0</license>
99

1010
<buildtool_depend>ament_cmake</buildtool_depend>
11+
<build_depend>nav2_common</build_depend>
1112

12-
<depend>nav2_common</depend>
1313
<depend>cv_bridge</depend>
14-
<depend>pluginlib</depend>
14+
<depend>geographic_msgs</depend>
15+
<depend>geometry_msgs</depend>
1516
<depend>image_transport</depend>
17+
<depend>nav2_core</depend>
18+
<depend>nav2_msgs</depend>
19+
<depend>nav2_util</depend>
20+
<depend>nav_msgs</depend>
21+
<depend>pluginlib</depend>
1622
<depend>rclcpp</depend>
1723
<depend>rclcpp_action</depend>
24+
<depend>rclcpp_components</depend>
1825
<depend>rclcpp_lifecycle</depend>
19-
<depend>nav_msgs</depend>
20-
<depend>nav2_msgs</depend>
21-
<depend>nav2_util</depend>
22-
<depend>nav2_core</depend>
23-
<depend>tf2_ros</depend>
2426
<depend>robot_localization</depend>
25-
<depend>geographic_msgs</depend>
26-
27-
<test_depend>ament_lint_common</test_depend>
28-
<test_depend>ament_lint_auto</test_depend>
27+
<depend>sensor_msgs</depend>
28+
<depend>std_msgs</depend>
29+
<depend>tf2_ros</depend>
30+
2931
<test_depend>ament_cmake_gtest</test_depend>
30-
<test_depend>ament_cmake_pytest</test_depend>
32+
<test_depend>ament_lint_auto</test_depend>
33+
<test_depend>ament_lint_common</test_depend>
3134

3235
<export>
3336
<build_type>ament_cmake</build_type>

nav2_waypoint_follower/test/CMakeLists.txt

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,20 +2,25 @@
22
ament_add_gtest(test_task_executors
33
test_task_executors.cpp
44
)
5-
ament_target_dependencies(test_task_executors
6-
${dependencies}
7-
)
85
target_link_libraries(test_task_executors
9-
${library_name} wait_at_waypoint photo_at_waypoint input_at_waypoint
6+
${library_name}
7+
wait_at_waypoint
8+
photo_at_waypoint
9+
input_at_waypoint
10+
${geometry_msgs_TARGETS}
11+
nav2_util::nav2_util_core
12+
rclcpp::rclcpp
13+
rclcpp_lifecycle::rclcpp_lifecycle
14+
${sensor_msgs_TARGETS}
1015
)
1116

1217
# Test dynamic parameters
1318
ament_add_gtest(test_dynamic_parameters
1419
test_dynamic_parameters.cpp
1520
)
16-
ament_target_dependencies(test_dynamic_parameters
17-
${dependencies}
18-
)
1921
target_link_libraries(test_dynamic_parameters
2022
${library_name}
23+
nav2_util::nav2_util_core
24+
rclcpp::rclcpp
25+
rclcpp_lifecycle::rclcpp_lifecycle
2126
)

0 commit comments

Comments
 (0)