Skip to content

Commit ba247b4

Browse files
authored
Revamp nav2_behavior_tree CMakeLists.txt to use modern idioms. (#4485)
This commit does a number of things: 1. Switches to using target_link_libraries everywhere. This gives us finer-grained control over what dependencies are exported to downstream as public, or private. In the particular case of nav2_behavior_tree, this actually doesn't matter *too* much, but it will help for other packages. 2. Moves the include directory down one level to include/${PROJECT_NAME}, which is best practice in ROS 2 since Humble. 3. Makes sure to export nav2_behavior_tree as a CMake target, so downstream users of it can use that target. 4. Removes the use of boost. To do this, we had to introduce our own version of the "split_string" method. 5. Moves the test_action_server.hpp file into the main include directory. This is slightly odd, but because downstream packages (opennav_docking_bt) depend on this header file to compile their own tests, it is technically part of the public interface. Signed-off-by: Chris Lalancette <clalancette@gmail.com>
1 parent f73fa24 commit ba247b4

39 files changed

+228
-287
lines changed

nav2_behavior_tree/CMakeLists.txt

Lines changed: 75 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -2,53 +2,46 @@ cmake_minimum_required(VERSION 3.5)
22
project(nav2_behavior_tree CXX)
33

44
find_package(ament_cmake REQUIRED)
5+
find_package(action_msgs REQUIRED)
6+
find_package(behaviortree_cpp REQUIRED)
7+
find_package(geometry_msgs REQUIRED)
58
find_package(nav2_common REQUIRED)
9+
find_package(nav2_msgs REQUIRED)
10+
find_package(nav2_util REQUIRED)
11+
find_package(nav_msgs REQUIRED)
612
find_package(rclcpp REQUIRED)
713
find_package(rclcpp_action REQUIRED)
814
find_package(rclcpp_lifecycle REQUIRED)
9-
find_package(builtin_interfaces REQUIRED)
10-
find_package(geometry_msgs REQUIRED)
1115
find_package(sensor_msgs REQUIRED)
12-
find_package(nav2_msgs REQUIRED)
13-
find_package(nav_msgs REQUIRED)
14-
find_package(behaviortree_cpp REQUIRED)
15-
find_package(tf2_ros REQUIRED)
16-
find_package(tf2_geometry_msgs REQUIRED)
1716
find_package(std_msgs REQUIRED)
1817
find_package(std_srvs REQUIRED)
19-
find_package(nav2_util REQUIRED)
18+
find_package(tf2 REQUIRED)
19+
find_package(tf2_ros REQUIRED)
2020

2121
nav2_package()
2222

23-
include_directories(
24-
include
25-
)
26-
2723
set(library_name ${PROJECT_NAME})
2824

29-
set(dependencies
30-
rclcpp
31-
rclcpp_action
32-
rclcpp_lifecycle
33-
geometry_msgs
34-
sensor_msgs
35-
nav2_msgs
36-
nav_msgs
37-
behaviortree_cpp
38-
tf2
39-
tf2_ros
40-
tf2_geometry_msgs
41-
std_msgs
42-
std_srvs
43-
nav2_util
44-
)
45-
4625
add_library(${library_name} SHARED
4726
src/behavior_tree_engine.cpp
4827
)
49-
50-
ament_target_dependencies(${library_name}
51-
${dependencies}
28+
target_include_directories(${library_name}
29+
PUBLIC
30+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
31+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
32+
target_link_libraries(${library_name} PUBLIC
33+
${action_msgs_TARGETS}
34+
behaviortree_cpp::behaviortree_cpp
35+
${geometry_msgs_TARGETS}
36+
${nav_msgs_TARGETS}
37+
${nav2_msgs_TARGETS}
38+
nav2_util::nav2_util_core
39+
rclcpp::rclcpp
40+
rclcpp_action::rclcpp_action
41+
rclcpp_lifecycle::rclcpp_lifecycle
42+
${sensor_msgs_TARGETS}
43+
tf2::tf2
44+
tf2_ros::tf2_ros
5245
)
5346

5447
add_library(nav2_compute_path_to_pose_action_bt_node SHARED plugins/action/compute_path_to_pose_action.cpp)
@@ -214,12 +207,30 @@ add_library(nav2_goal_updated_controller_bt_node SHARED plugins/decorator/goal_u
214207
list(APPEND plugin_libs nav2_goal_updated_controller_bt_node)
215208

216209
foreach(bt_plugin ${plugin_libs})
217-
ament_target_dependencies(${bt_plugin} ${dependencies})
210+
target_include_directories(${bt_plugin}
211+
PRIVATE
212+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
213+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
214+
target_link_libraries(${bt_plugin} PUBLIC
215+
behaviortree_cpp::behaviortree_cpp
216+
${geometry_msgs_TARGETS}
217+
${nav_msgs_TARGETS}
218+
${nav2_msgs_TARGETS}
219+
nav2_util::nav2_util_core
220+
rclcpp::rclcpp
221+
rclcpp_action::rclcpp_action
222+
rclcpp_lifecycle::rclcpp_lifecycle
223+
${sensor_msgs_TARGETS}
224+
tf2::tf2
225+
tf2_ros::tf2_ros
226+
${std_msgs_TARGETS}
227+
${std_srvs_TARGETS}
228+
)
218229
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
219230
endforeach()
220231

221-
install(TARGETS ${library_name}
222-
${plugin_libs}
232+
install(TARGETS ${library_name} ${plugin_libs}
233+
EXPORT ${library_name}
223234
ARCHIVE DESTINATION lib
224235
LIBRARY DESTINATION lib
225236
RUNTIME DESTINATION bin
@@ -230,39 +241,54 @@ set(GENERATED_DIR ${CMAKE_CURRENT_BINARY_DIR}/gen)
230241
configure_file(plugins_list.hpp.in ${GENERATED_DIR}/plugins_list.hpp)
231242

232243
add_executable(generate_nav2_tree_nodes_xml src/generate_nav2_tree_nodes_xml.cpp)
233-
ament_target_dependencies(generate_nav2_tree_nodes_xml ${dependencies})
244+
target_link_libraries(generate_nav2_tree_nodes_xml PRIVATE
245+
behaviortree_cpp::behaviortree_cpp
246+
nav2_util::nav2_util_core
247+
)
234248
# allow generate_nav2_tree_nodes_xml to find plugins_list.hpp
235249
target_include_directories(generate_nav2_tree_nodes_xml PRIVATE ${GENERATED_DIR})
236250
install(TARGETS generate_nav2_tree_nodes_xml DESTINATION lib/${PROJECT_NAME})
237251

238-
239252
install(DIRECTORY include/
240-
DESTINATION include/
241-
)
242-
243-
install(DIRECTORY test/utils/
244-
DESTINATION include/${PROJECT_NAME}/utils/
253+
DESTINATION include/${PROJECT_NAME}
245254
)
246255

247256
install(FILES nav2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})
248-
install(FILES ${GENERATED_DIR}/plugins_list.hpp DESTINATION include/${PROJECT_NAME})
257+
install(FILES ${GENERATED_DIR}/plugins_list.hpp DESTINATION include/${PROJECT_NAME}/${PROJECT_NAME})
249258

250259
if(BUILD_TESTING)
251260
find_package(ament_lint_auto REQUIRED)
252261
ament_lint_auto_find_test_dependencies()
253262
find_package(ament_cmake_gtest REQUIRED)
263+
264+
ament_find_gtest()
265+
254266
add_subdirectory(test)
255267
endif()
256268

257269
ament_export_include_directories(
258-
include
270+
include/${PROJECT_NAME}
259271
)
260272

261-
ament_export_libraries(
262-
${library_name}
263-
${plugin_libs}
264-
)
273+
ament_export_libraries(${library_name})
265274

266-
ament_export_dependencies(${dependencies})
275+
ament_export_dependencies(
276+
action_msgs
277+
behaviortree_cpp
278+
geometry_msgs
279+
nav2_common
280+
nav2_msgs
281+
nav2_util
282+
nav_msgs
283+
rclcpp
284+
rclcpp_action
285+
rclcpp_lifecycle
286+
sensor_msgs
287+
std_msgs
288+
std_srvs
289+
tf2
290+
tf2_ros
291+
)
292+
ament_export_targets(${library_name})
267293

268294
ament_package()

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp

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

18+
#include <chrono>
19+
#include <functional>
1820
#include <memory>
1921
#include <string>
2022
#include <vector>
@@ -24,6 +26,8 @@
2426
#include "nav2_behavior_tree/ros_topic_logger.hpp"
2527
#include "nav2_util/lifecycle_node.hpp"
2628
#include "nav2_util/simple_action_server.hpp"
29+
#include "rclcpp/rclcpp.hpp"
30+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
2731

2832
namespace nav2_behavior_tree
2933
{

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,18 +15,20 @@
1515
#ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
1616
#define NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
1717

18-
#include <memory>
19-
#include <string>
18+
#include <chrono>
19+
#include <exception>
2020
#include <fstream>
21+
#include <limits>
22+
#include <memory>
2123
#include <set>
22-
#include <exception>
24+
#include <string>
2325
#include <vector>
24-
#include <limits>
2526

2627
#include "nav2_msgs/action/navigate_to_pose.hpp"
2728
#include "nav2_behavior_tree/bt_action_server.hpp"
28-
#include "ament_index_cpp/get_package_share_directory.hpp"
2929
#include "nav2_util/node_utils.hpp"
30+
#include "rcl_action/action_server.h"
31+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
3032

3133
namespace nav2_behavior_tree
3234
{

nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "rclcpp/rclcpp.hpp"
2424
#include "nav2_msgs/msg/behavior_tree_log.hpp"
2525
#include "nav2_msgs/msg/behavior_tree_status_change.h"
26+
#include "tf2/time.h"
2627
#include "tf2_ros/buffer_interface.h"
2728

2829
namespace nav2_behavior_tree

nav2_behavior_tree/test/utils/test_action_server.hpp renamed to nav2_behavior_tree/include/nav2_behavior_tree/utils/test_action_server.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef UTILS__TEST_ACTION_SERVER_HPP_
16-
#define UTILS__TEST_ACTION_SERVER_HPP_
15+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_
16+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_
1717

1818
#include <string>
1919
#include <memory>
@@ -97,4 +97,4 @@ class TestActionServer : public rclcpp::Node
9797
bool goal_cancelled_ = false;
9898
};
9999

100-
#endif // UTILS__TEST_ACTION_SERVER_HPP_
100+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_

nav2_behavior_tree/package.xml

Lines changed: 16 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -11,46 +11,26 @@
1111

1212
<buildtool_depend>ament_cmake</buildtool_depend>
1313

14-
<build_export_depend>tf2_geometry_msgs</build_export_depend>
15-
<build_export_depend>std_srvs</build_export_depend>
16-
17-
<build_depend>rclcpp</build_depend>
18-
<build_depend>rclcpp_action</build_depend>
19-
<build_depend>rclcpp_lifecycle</build_depend>
20-
<build_depend>behaviortree_cpp</build_depend>
21-
<build_depend>builtin_interfaces</build_depend>
22-
<build_depend>geometry_msgs</build_depend>
23-
<build_depend>sensor_msgs</build_depend>
24-
<build_depend>nav2_msgs</build_depend>
25-
<build_depend>nav_msgs</build_depend>
26-
<build_depend>tf2</build_depend>
27-
<build_depend>tf2_ros</build_depend>
28-
<build_depend>tf2_geometry_msgs</build_depend>
29-
<build_depend>std_msgs</build_depend>
30-
<build_depend>std_srvs</build_depend>
31-
<build_depend>nav2_util</build_depend>
32-
<build_depend>lifecycle_msgs</build_depend>
33-
<build_depend>nav2_common</build_depend>
34-
35-
<exec_depend>rclcpp</exec_depend>
36-
<exec_depend>rclcpp_action</exec_depend>
37-
<exec_depend>rclcpp_lifecycle</exec_depend>
38-
<exec_depend>std_msgs</exec_depend>
39-
<exec_depend>behaviortree_cpp</exec_depend>
40-
<exec_depend>builtin_interfaces</exec_depend>
41-
<exec_depend>geometry_msgs</exec_depend>
42-
<exec_depend>sensor_msgs</exec_depend>
43-
<exec_depend>nav2_msgs</exec_depend>
44-
<exec_depend>nav_msgs</exec_depend>
45-
<exec_depend>tf2</exec_depend>
46-
<exec_depend>tf2_ros</exec_depend>
47-
<exec_depend>tf2_geometry_msgs</exec_depend>
48-
<exec_depend>nav2_util</exec_depend>
49-
<exec_depend>lifecycle_msgs</exec_depend>
14+
<depend>action_msgs</depend>
15+
<depend>behaviortree_cpp</depend>
16+
<depend>geometry_msgs</depend>
17+
<depend>nav2_common</depend>
18+
<depend>nav2_msgs</depend>
19+
<depend>nav2_util</depend>
20+
<depend>nav_msgs</depend>
21+
<depend>rclcpp</depend>
22+
<depend>rclcpp_action</depend>
23+
<depend>rclcpp_lifecycle</depend>
24+
<depend>sensor_msgs</depend>
25+
<depend>std_msgs</depend>
26+
<depend>std_srvs</depend>
27+
<depend>tf2</depend>
28+
<depend>tf2_ros</depend>
5029

5130
<test_depend>ament_lint_common</test_depend>
5231
<test_depend>ament_lint_auto</test_depend>
5332
<test_depend>ament_cmake_gtest</test_depend>
33+
<test_depend>lifecycle_msgs</test_depend>
5434
<test_depend>test_msgs</test_depend>
5535

5636
<export>

nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <cmath>
1516
#include <limits>
1617
#include <memory>
1718
#include <string>
@@ -22,6 +23,9 @@
2223
#include "nav2_util/geometry_utils.hpp"
2324
#include "nav2_util/robot_utils.hpp"
2425
#include "nav_msgs/msg/path.hpp"
26+
#include "rclcpp/rclcpp.hpp"
27+
#include "tf2/LinearMath/Quaternion.h"
28+
#include "tf2_ros/buffer.h"
2529
#include "tf2_ros/create_timer_ros.h"
2630

2731
#include "nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp"

nav2_behavior_tree/plugins/condition/transform_available_condition.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <string>
1615
#include <chrono>
1716
#include <memory>
17+
#include <string>
18+
19+
#include "rclcpp/rclcpp.hpp"
20+
#include "tf2/time.h"
21+
#include "tf2_ros/buffer.h"
1822

1923
#include "nav2_behavior_tree/plugins/condition/transform_available_condition.hpp"
2024

nav2_behavior_tree/test/CMakeLists.txt

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,22 @@
11
ament_add_gtest(test_bt_utils test_bt_utils.cpp)
2-
ament_target_dependencies(test_bt_utils ${dependencies})
2+
target_link_libraries(test_bt_utils
3+
${library_name}
4+
${geometry_msgs_TARGETS}
5+
)
36

4-
include_directories(.)
7+
function(plugin_add_test target filename plugin)
8+
ament_add_gtest(${target} ${filename})
9+
target_link_libraries(${target}
10+
${geometry_msgs_TARGETS}
11+
nav2_util::nav2_util_core
12+
behaviortree_cpp::behaviortree_cpp
13+
${library_name}
14+
${plugin}
15+
)
16+
target_include_directories(${target}
17+
PRIVATE
18+
"$<BUILD_INTERFACE:${CMAKE_SOURCE_DIR}/test>")
19+
endfunction()
520

621
add_subdirectory(plugins/condition)
722
add_subdirectory(plugins/decorator)

0 commit comments

Comments
 (0)