Skip to content

Commit c81ba02

Browse files
committed
Fix BT.CPP upgrade
1 parent d06a703 commit c81ba02

File tree

8 files changed

+10
-10
lines changed

8 files changed

+10
-10
lines changed

Diff for: opennav_coverage_bt/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ find_package(nav2_behavior_tree REQUIRED)
1212
find_package(nav_msgs REQUIRED)
1313
find_package(geometry_msgs REQUIRED)
1414
find_package(opennav_coverage_msgs REQUIRED)
15-
find_package(behaviortree_cpp_v3 REQUIRED)
15+
find_package(behaviortree_cpp REQUIRED)
1616

1717
# potentially replace with nav2_common, nav2_package()
1818
set(CMAKE_CXX_STANDARD 17)
@@ -33,7 +33,7 @@ set(dependencies
3333
nav_msgs
3434
geometry_msgs
3535
opennav_coverage_msgs
36-
behaviortree_cpp_v3
36+
behaviortree_cpp
3737
)
3838

3939
add_library(opennav_compute_complete_coverage_action_bt_node SHARED src/compute_complete_coverage_path.cpp)

Diff for: opennav_coverage_bt/include/opennav_coverage_bt/utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
#define OPENNAV_COVERAGE_BT__UTILS_HPP_
1717

1818
#include <charconv>
19-
#include "behaviortree_cpp_v3/behavior_tree.h"
19+
#include "behaviortree_cpp/behavior_tree.h"
2020

2121
namespace BT
2222
{

Diff for: opennav_coverage_bt/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
<depend>nav_msgs</depend>
1919
<depend>geometry_msgs</depend>
2020
<depend>opennav_coverage_msgs</depend>
21-
<depend>behaviortree_cpp_v3</depend>
21+
<depend>behaviortree_cpp</depend>
2222

2323
<test_depend>ament_lint_common</test_depend>
2424
<test_depend>ament_lint_auto</test_depend>

Diff for: opennav_coverage_bt/src/cancel_complete_coverage_path.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ CoverageCancel::CoverageCancel(
3131

3232
} // namespace opennav_coverage_bt
3333

34-
#include "behaviortree_cpp_v3/bt_factory.h"
34+
#include "behaviortree_cpp/bt_factory.h"
3535
BT_REGISTER_NODES(factory)
3636
{
3737
BT::NodeBuilder builder =

Diff for: opennav_coverage_bt/src/compute_complete_coverage_path.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ void ComputeCoveragePathAction::halt()
9898

9999
} // namespace opennav_coverage_bt
100100

101-
#include "behaviortree_cpp_v3/bt_factory.h"
101+
#include "behaviortree_cpp/bt_factory.h"
102102
BT_REGISTER_NODES(factory)
103103
{
104104
BT::NodeBuilder builder =

Diff for: opennav_coverage_bt/test/test_cancel_complete_coverage.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
#include <set>
1818
#include <string>
1919

20-
#include "behaviortree_cpp_v3/bt_factory.h"
20+
#include "behaviortree_cpp/bt_factory.h"
2121

2222
#include "nav2_behavior_tree/utils/test_action_server.hpp"
2323
#include "opennav_coverage_bt/cancel_complete_coverage_path.hpp"

Diff for: opennav_coverage_bt/test/test_compute_coverage_path.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
#include "nav_msgs/msg/path.hpp"
2121
#include "geometry_msgs/msg/pose_stamped.hpp"
2222

23-
#include "behaviortree_cpp_v3/bt_factory.h"
23+
#include "behaviortree_cpp/bt_factory.h"
2424

2525
#include "nav2_behavior_tree/utils/test_action_server.hpp"
2626
#include "opennav_coverage_bt/compute_complete_coverage_path.hpp"

Diff for: opennav_coverage_navigator/src/coverage_navigator.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ CoverageNavigator::onLoop()
122122
try {
123123
// Get current path points
124124
nav_msgs::msg::Path current_path;
125-
blackboard->get<nav_msgs::msg::Path>(path_blackboard_id_, current_path);
125+
[[maybe_unused]] auto res = blackboard->get(path_blackboard_id_, current_path);
126126

127127
// Find the closest pose to current pose on global path
128128
auto find_closest_pose_idx =
@@ -165,7 +165,7 @@ CoverageNavigator::onLoop()
165165
}
166166

167167
int recovery_count = 0;
168-
blackboard->get<int>("number_recoveries", recovery_count);
168+
[[maybe_unused]] auto result = blackboard->get("number_recoveries", recovery_count);
169169
feedback_msg->number_of_recoveries = recovery_count;
170170
feedback_msg->current_pose = current_pose;
171171
feedback_msg->navigation_time = clock_->now() - start_time_;

0 commit comments

Comments
 (0)