16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__CONTROLLER_SELECTOR_NODE_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__CONTROLLER_SELECTOR_NODE_HPP_
22 #include "std_msgs/msg/string.hpp"
24 #include "behaviortree_cpp_v3/action_node.h"
26 #include "rclcpp/rclcpp.hpp"
28 namespace nav2_behavior_tree
48 const std::string & xml_tag_name,
49 const BT::NodeConfiguration & conf);
58 BT::InputPort<std::string>(
60 "the default controller to use if there is not any external topic message received."),
62 BT::InputPort<std::string>(
64 "controller_selector",
65 "the input topic name to select the controller"),
67 BT::OutputPort<std::string>(
68 "selected_controller",
69 "Selected controller by subscription")
77 BT::NodeStatus tick()
override;
84 void callbackControllerSelect(
const std_msgs::msg::String::SharedPtr msg);
86 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr controller_selector_sub_;
88 std::string last_selected_controller_;
90 rclcpp::Node::SharedPtr node_;
91 rclcpp::CallbackGroup::SharedPtr callback_group_;
92 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
94 std::string topic_name_;
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.
static BT::PortsList providedPorts()
Creates list of BT ports.