Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
controller_selector_node.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Pablo IƱigo Blasco
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <string>
17 #include <memory>
18 
19 #include "std_msgs/msg/string.hpp"
20 
21 #include "nav2_behavior_tree/plugins/action/controller_selector_node.hpp"
22 
23 #include "rclcpp/rclcpp.hpp"
24 
25 namespace nav2_behavior_tree
26 {
27 
28 using std::placeholders::_1;
29 
31  const std::string & name,
32  const BT::NodeConfiguration & conf)
33 : BT::SyncActionNode(name, conf)
34 {
35  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  getInput("topic_name", topic_name_);
42 
43  rclcpp::QoS qos(rclcpp::KeepLast(1));
44  qos.transient_local().reliable();
45 
46  rclcpp::SubscriptionOptions sub_option;
47  sub_option.callback_group = callback_group_;
48  controller_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
49  topic_name_,
50  qos,
51  std::bind(&ControllerSelector::callbackControllerSelect, this, _1),
52  sub_option);
53 }
54 
55 BT::NodeStatus ControllerSelector::tick()
56 {
57  callback_group_executor_.spin_some();
58 
59  // This behavior always use the last selected controller received from the topic input.
60  // When no input is specified it uses the default controller.
61  // If the default controller is not specified then we work in "required controller mode":
62  // In this mode, the behavior returns failure if the controller selection is not received from
63  // the topic input.
64  if (last_selected_controller_.empty()) {
65  std::string default_controller;
66  getInput("default_controller", default_controller);
67  if (default_controller.empty()) {
68  return BT::NodeStatus::FAILURE;
69  } else {
70  last_selected_controller_ = default_controller;
71  }
72  }
73 
74  setOutput("selected_controller", last_selected_controller_);
75 
76  return BT::NodeStatus::SUCCESS;
77 }
78 
79 void
80 ControllerSelector::callbackControllerSelect(const std_msgs::msg::String::SharedPtr msg)
81 {
82  last_selected_controller_ = msg->data;
83 }
84 
85 } // namespace nav2_behavior_tree
86 
87 #include "behaviortree_cpp_v3/bt_factory.h"
88 BT_REGISTER_NODES(factory)
89 {
90  factory.registerNodeType<nav2_behavior_tree::ControllerSelector>("ControllerSelector");
91 }
The ControllerSelector behavior is used to switch the controller that will be used by the controller ...
ControllerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ControllerSelector.