19 #include "std_msgs/msg/string.hpp"
21 #include "nav2_behavior_tree/plugins/action/planner_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)
35 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
36 callback_group_ = node_->create_callback_group(
37 rclcpp::CallbackGroupType::MutuallyExclusive,
39 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
41 getInput(
"topic_name", topic_name_);
43 rclcpp::QoS qos(rclcpp::KeepLast(1));
44 qos.transient_local().reliable();
46 rclcpp::SubscriptionOptions sub_option;
47 sub_option.callback_group = callback_group_;
48 planner_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
51 std::bind(&PlannerSelector::callbackPlannerSelect,
this, _1),
55 BT::NodeStatus PlannerSelector::tick()
57 callback_group_executor_.spin_some();
64 if (last_selected_planner_.empty()) {
65 std::string default_planner;
66 getInput(
"default_planner", default_planner);
67 if (default_planner.empty()) {
68 return BT::NodeStatus::FAILURE;
70 last_selected_planner_ = default_planner;
74 setOutput(
"selected_planner", last_selected_planner_);
76 return BT::NodeStatus::SUCCESS;
80 PlannerSelector::callbackPlannerSelect(
const std_msgs::msg::String::SharedPtr msg)
82 last_selected_planner_ = msg->data;
87 #include "behaviortree_cpp_v3/bt_factory.h"
88 BT_REGISTER_NODES(factory)
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.