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)
38 callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
41 void PlannerSelector::initialize()
43 createROSInterfaces();
46 void PlannerSelector::createROSInterfaces()
48 std::string topic_new;
49 getInput(
"topic_name", topic_new);
50 if (topic_new != topic_name_ || !planner_selector_sub_) {
51 topic_name_ = topic_new;
52 node_ = config().blackboard->get<nav2::LifecycleNode::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());
58 planner_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
60 std::bind(&PlannerSelector::callbackPlannerSelect,
this, _1),
66 BT::NodeStatus PlannerSelector::tick()
68 if (!BT::isStatusActive(status())) {
72 callback_group_executor_.spin_some();
79 if (last_selected_planner_.empty()) {
80 std::string default_planner;
81 getInput(
"default_planner", default_planner);
82 if (default_planner.empty()) {
83 return BT::NodeStatus::FAILURE;
85 last_selected_planner_ = default_planner;
89 setOutput(
"selected_planner", last_selected_planner_);
91 return BT::NodeStatus::SUCCESS;
95 PlannerSelector::callbackPlannerSelect(
const std_msgs::msg::String::SharedPtr msg)
97 last_selected_planner_ = msg->data;
102 #include "behaviortree_cpp/bt_factory.h"
103 BT_REGISTER_NODES(factory)
A QoS profile for latched, reliable topics with a history of 10 messages.
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.