16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PLANNER_SELECTOR_NODE_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PLANNER_SELECTOR_NODE_HPP_
23 #include "std_msgs/msg/string.hpp"
25 #include "behaviortree_cpp/action_node.h"
27 #include "nav2_ros_common/lifecycle_node.hpp"
29 namespace nav2_behavior_tree
50 const std::string & xml_tag_name,
51 const BT::NodeConfiguration & conf);
60 BT::InputPort<std::string>(
62 "the default planner to use if there is not any external topic message received."),
64 BT::InputPort<std::string>(
67 "the input topic name to select the planner"),
69 BT::OutputPort<std::string>(
71 "Selected planner by subscription")
83 void createROSInterfaces();
88 BT::NodeStatus tick()
override;
95 void callbackPlannerSelect(
const std_msgs::msg::String::SharedPtr msg);
98 nav2::Subscription<std_msgs::msg::String>::SharedPtr planner_selector_sub_;
100 std::string last_selected_planner_;
102 nav2::LifecycleNode::SharedPtr node_;
103 rclcpp::CallbackGroup::SharedPtr callback_group_;
104 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
106 std::string topic_name_;
107 std::chrono::milliseconds bt_loop_duration_;
The PlannerSelector behavior is used to switch the planner that will be used by the planner server....
PlannerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::PlannerSelector.
static BT::PortsList providedPorts()
Creates list of BT ports.