19 #include "std_msgs/msg/string.hpp"
21 #include "nav2_behavior_tree/plugins/action/controller_selector_node.hpp"
23 #include "rclcpp/rclcpp.hpp"
25 namespace nav2_behavior_tree
28 using std::placeholders::_1;
31 const std::string & name,
32 const BT::NodeConfiguration & conf)
33 : BT::SyncActionNode(name, conf)
38 callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
41 void ControllerSelector::initialize()
43 createROSInterfaces();
46 void ControllerSelector::createROSInterfaces()
48 std::string topic_new;
49 getInput(
"topic_name", topic_new);
50 if (topic_new != topic_name_ || !controller_selector_sub_) {
51 topic_name_ = topic_new;
52 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
53 callback_group_ = node_->create_callback_group(
54 rclcpp::CallbackGroupType::MutuallyExclusive,
56 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
59 rclcpp::QoS qos(rclcpp::KeepLast(1));
60 qos.transient_local().reliable();
62 rclcpp::SubscriptionOptions sub_option;
63 sub_option.callback_group = callback_group_;
64 controller_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
67 std::bind(&ControllerSelector::callbackControllerSelect,
this, _1),
72 BT::NodeStatus ControllerSelector::tick()
74 if (!BT::isStatusActive(status())) {
78 callback_group_executor_.spin_some();
85 if (last_selected_controller_.empty()) {
86 std::string default_controller;
87 getInput(
"default_controller", default_controller);
88 if (default_controller.empty()) {
89 return BT::NodeStatus::FAILURE;
91 last_selected_controller_ = default_controller;
95 setOutput(
"selected_controller", last_selected_controller_);
97 return BT::NodeStatus::SUCCESS;
101 ControllerSelector::callbackControllerSelect(
const std_msgs::msg::String::SharedPtr msg)
103 last_selected_controller_ = msg->data;
108 #include "behaviortree_cpp/bt_factory.h"
109 BT_REGISTER_NODES(factory)
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.