Skip to content

Commit c88f45a

Browse files
Update BT nodes to use callback groups / executors to process (#2334)
* Update BT nodes to use callback groups / executors to process implement #2251 * add executor to other BT nodes * use spin_some in is_battery_low BT condition * fix merge * remove spinning thread
1 parent 2fcc2c2 commit c88f45a

File tree

12 files changed

+97
-22
lines changed

12 files changed

+97
-22
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,10 @@ class BtActionNode : public BT::ActionNodeBase
4747
: BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name)
4848
{
4949
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
50+
callback_group_ = node_->create_callback_group(
51+
rclcpp::CallbackGroupType::MutuallyExclusive,
52+
false);
53+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
5054

5155
// Get the required items from the blackboard
5256
bt_loop_duration_ =
@@ -82,7 +86,7 @@ class BtActionNode : public BT::ActionNodeBase
8286
void createActionClient(const std::string & action_name)
8387
{
8488
// Now that we have the ROS node to use, create the action client for this BT action
85-
action_client_ = rclcpp_action::create_client<ActionT>(node_, action_name);
89+
action_client_ = rclcpp_action::create_client<ActionT>(node_, action_name, callback_group_);
8690

8791
// Make sure the server is actually there before continuing
8892
RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
@@ -223,7 +227,7 @@ class BtActionNode : public BT::ActionNodeBase
223227
}
224228
}
225229

226-
rclcpp::spin_some(node_);
230+
callback_group_executor_.spin_some();
227231

228232
// check if, after invoking spin_some(), we finally received the result
229233
if (!goal_result_available_) {
@@ -262,7 +266,7 @@ class BtActionNode : public BT::ActionNodeBase
262266
{
263267
if (should_cancel_goal()) {
264268
auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
265-
if (rclcpp::spin_until_future_complete(node_, future_cancel, server_timeout_) !=
269+
if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
266270
rclcpp::FutureReturnCode::SUCCESS)
267271
{
268272
RCLCPP_ERROR(
@@ -291,7 +295,7 @@ class BtActionNode : public BT::ActionNodeBase
291295
return false;
292296
}
293297

294-
rclcpp::spin_some(node_);
298+
callback_group_executor_.spin_some();
295299
auto status = goal_handle_->get_status();
296300

297301
// Check if the goal is still executing
@@ -340,7 +344,8 @@ class BtActionNode : public BT::ActionNodeBase
340344
}
341345

342346
auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining;
343-
auto result = rclcpp::spin_until_future_complete(node_, *future_goal_handle_, timeout);
347+
auto result =
348+
callback_group_executor_.spin_until_future_complete(*future_goal_handle_, timeout);
344349
elapsed += timeout;
345350

346351
if (result == rclcpp::FutureReturnCode::INTERRUPTED) {
@@ -383,6 +388,8 @@ class BtActionNode : public BT::ActionNodeBase
383388

384389
// The node that will be used for any ROS operations
385390
rclcpp::Node::SharedPtr node_;
391+
rclcpp::CallbackGroup::SharedPtr callback_group_;
392+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
386393

387394
// The timeout value while waiting for response from a server when a
388395
// new action goal is sent or canceled

nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,10 @@ class BtServiceNode : public BT::ActionNodeBase
4545
: BT::ActionNodeBase(service_node_name, conf), service_node_name_(service_node_name)
4646
{
4747
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
48+
callback_group_ = node_->create_callback_group(
49+
rclcpp::CallbackGroupType::MutuallyExclusive,
50+
false);
51+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
4852

4953
// Get the required items from the blackboard
5054
bt_loop_duration_ =
@@ -55,7 +59,10 @@ class BtServiceNode : public BT::ActionNodeBase
5559

5660
// Now that we have node_ to use, create the service client for this BT service
5761
getInput("service_name", service_name_);
58-
service_client_ = node_->create_client<ServiceT>(service_name_);
62+
service_client_ = node_->create_client<ServiceT>(
63+
service_name_,
64+
rmw_qos_profile_services_default,
65+
callback_group_);
5966

6067
// Make a request for the service without parameter
6168
request_ = std::make_shared<typename ServiceT::Request>();
@@ -147,7 +154,8 @@ class BtServiceNode : public BT::ActionNodeBase
147154
if (remaining > std::chrono::milliseconds(0)) {
148155
auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining;
149156

150-
auto rc = rclcpp::spin_until_future_complete(node_, future_result_, timeout);
157+
rclcpp::FutureReturnCode rc;
158+
rc = callback_group_executor_.spin_until_future_complete(future_result_, server_timeout_);
151159
if (rc == rclcpp::FutureReturnCode::SUCCESS) {
152160
request_sent_ = false;
153161
return BT::NodeStatus::SUCCESS;
@@ -195,6 +203,8 @@ class BtServiceNode : public BT::ActionNodeBase
195203

196204
// The node that will be used for any ROS operations
197205
rclcpp::Node::SharedPtr node_;
206+
rclcpp::CallbackGroup::SharedPtr callback_group_;
207+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
198208

199209
// The timeout value while to use in the tick loop while waiting for
200210
// a result from the server

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,8 @@ class ControllerSelector : public BT::SyncActionNode
8888
std::string last_selected_controller_;
8989

9090
rclcpp::Node::SharedPtr node_;
91+
rclcpp::CallbackGroup::SharedPtr callback_group_;
92+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
9193

9294
std::string topic_name_;
9395
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,8 @@ class PlannerSelector : public BT::SyncActionNode
8989
std::string last_selected_planner_;
9090

9191
rclcpp::Node::SharedPtr node_;
92+
rclcpp::CallbackGroup::SharedPtr callback_group_;
93+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
9294

9395
std::string topic_name_;
9496
};

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,12 +74,13 @@ class IsBatteryLowCondition : public BT::ConditionNode
7474
void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
7575

7676
rclcpp::Node::SharedPtr node_;
77+
rclcpp::CallbackGroup::SharedPtr callback_group_;
78+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
7779
rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
7880
std::string battery_topic_;
7981
double min_battery_;
8082
bool is_voltage_;
8183
bool is_battery_low_;
82-
std::mutex mutex_;
8384
};
8485

8586
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,9 @@ class IsStuckCondition : public BT::ConditionNode
8686
private:
8787
// The node that will be used for any ROS operations
8888
rclcpp::Node::SharedPtr node_;
89+
rclcpp::CallbackGroup::SharedPtr callback_group_;
90+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
91+
std::thread callback_group_executor_thread;
8992

9093
std::atomic<bool> is_stuck_;
9194

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,10 @@ class GoalUpdater : public BT::DecoratorNode
7474
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;
7575

7676
geometry_msgs::msg::PoseStamped last_goal_received_;
77+
78+
rclcpp::Node::SharedPtr node_;
79+
rclcpp::CallbackGroup::SharedPtr callback_group_;
80+
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
7781
};
7882

7983
} // namespace nav2_behavior_tree

nav2_behavior_tree/plugins/action/controller_selector_node.cpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,19 +33,28 @@ ControllerSelector::ControllerSelector(
3333
: BT::SyncActionNode(name, conf)
3434
{
3535
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
36+
callback_group_ = node_->create_callback_group(
37+
rclcpp::CallbackGroupType::MutuallyExclusive,
38+
false);
39+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
3640

3741
getInput("topic_name", topic_name_);
3842

3943
rclcpp::QoS qos(rclcpp::KeepLast(1));
4044
qos.transient_local().reliable();
4145

46+
rclcpp::SubscriptionOptions sub_option;
47+
sub_option.callback_group = callback_group_;
4248
controller_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
43-
topic_name_, qos, std::bind(&ControllerSelector::callbackControllerSelect, this, _1));
49+
topic_name_,
50+
qos,
51+
std::bind(&ControllerSelector::callbackControllerSelect, this, _1),
52+
sub_option);
4453
}
4554

4655
BT::NodeStatus ControllerSelector::tick()
4756
{
48-
rclcpp::spin_some(node_);
57+
callback_group_executor_.spin_some();
4958

5059
// This behavior always use the last selected controller received from the topic input.
5160
// When no input is specified it uses the default controller.

nav2_behavior_tree/plugins/action/planner_selector_node.cpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,19 +33,28 @@ PlannerSelector::PlannerSelector(
3333
: BT::SyncActionNode(name, conf)
3434
{
3535
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
36+
callback_group_ = node_->create_callback_group(
37+
rclcpp::CallbackGroupType::MutuallyExclusive,
38+
false);
39+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
3640

3741
getInput("topic_name", topic_name_);
3842

3943
rclcpp::QoS qos(rclcpp::KeepLast(1));
4044
qos.transient_local().reliable();
4145

46+
rclcpp::SubscriptionOptions sub_option;
47+
sub_option.callback_group = callback_group_;
4248
planner_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
43-
topic_name_, qos, std::bind(&PlannerSelector::callbackPlannerSelect, this, _1));
49+
topic_name_,
50+
qos,
51+
std::bind(&PlannerSelector::callbackPlannerSelect, this, _1),
52+
sub_option);
4453
}
4554

4655
BT::NodeStatus PlannerSelector::tick()
4756
{
48-
rclcpp::spin_some(node_);
57+
callback_group_executor_.spin_some();
4958

5059
// This behavior always use the last selected planner received from the topic input.
5160
// When no input is specified it uses the default planner.

nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,15 +33,23 @@ IsBatteryLowCondition::IsBatteryLowCondition(
3333
getInput("battery_topic", battery_topic_);
3434
getInput("is_voltage", is_voltage_);
3535
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
36+
callback_group_ = node_->create_callback_group(
37+
rclcpp::CallbackGroupType::MutuallyExclusive,
38+
false);
39+
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
40+
41+
rclcpp::SubscriptionOptions sub_option;
42+
sub_option.callback_group = callback_group_;
3643
battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
3744
battery_topic_,
3845
rclcpp::SystemDefaultsQoS(),
39-
std::bind(&IsBatteryLowCondition::batteryCallback, this, std::placeholders::_1));
46+
std::bind(&IsBatteryLowCondition::batteryCallback, this, std::placeholders::_1),
47+
sub_option);
4048
}
4149

4250
BT::NodeStatus IsBatteryLowCondition::tick()
4351
{
44-
std::lock_guard<std::mutex> lock(mutex_);
52+
callback_group_executor_.spin_some();
4553
if (is_battery_low_) {
4654
return BT::NodeStatus::SUCCESS;
4755
}
@@ -50,7 +58,6 @@ BT::NodeStatus IsBatteryLowCondition::tick()
5058

5159
void IsBatteryLowCondition::batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg)
5260
{
53-
std::lock_guard<std::mutex> lock(mutex_);
5461
if (is_voltage_) {
5562
is_battery_low_ = msg->voltage <= min_battery_;
5663
} else {

0 commit comments

Comments
 (0)