Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
planner_selector_node.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Pablo IƱigo Blasco
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <string>
17 #include <memory>
18 
19 #include "std_msgs/msg/string.hpp"
20 
21 #include "nav2_behavior_tree/plugins/action/planner_selector_node.hpp"
22 
23 #include "rclcpp/rclcpp.hpp"
24 
25 namespace nav2_behavior_tree
26 {
27 
28 using std::placeholders::_1;
29 
31  const std::string & name,
32  const BT::NodeConfiguration & conf)
33 : BT::SyncActionNode(name, conf)
34 {
35  initialize();
36 
37  // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
38  callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
39 }
40 
41 void PlannerSelector::initialize()
42 {
43  createROSInterfaces();
44 }
45 
46 void PlannerSelector::createROSInterfaces()
47 {
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<rclcpp::Node::SharedPtr>("node");
53  callback_group_ = node_->create_callback_group(
54  rclcpp::CallbackGroupType::MutuallyExclusive,
55  false);
56  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 
58  rclcpp::QoS qos(rclcpp::KeepLast(1));
59  qos.transient_local().reliable();
60 
61  rclcpp::SubscriptionOptions sub_option;
62  sub_option.callback_group = callback_group_;
63  planner_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
64  topic_name_,
65  qos,
66  std::bind(&PlannerSelector::callbackPlannerSelect, this, _1),
67  sub_option);
68  }
69 }
70 
71 BT::NodeStatus PlannerSelector::tick()
72 {
73  if (!BT::isStatusActive(status())) {
74  initialize();
75  }
76 
77  callback_group_executor_.spin_some();
78 
79  // This behavior always use the last selected planner received from the topic input.
80  // When no input is specified it uses the default planner.
81  // If the default planner is not specified then we work in "required planner mode":
82  // In this mode, the behavior returns failure if the planner selection is not received from
83  // the topic input.
84  if (last_selected_planner_.empty()) {
85  std::string default_planner;
86  getInput("default_planner", default_planner);
87  if (default_planner.empty()) {
88  return BT::NodeStatus::FAILURE;
89  } else {
90  last_selected_planner_ = default_planner;
91  }
92  }
93 
94  setOutput("selected_planner", last_selected_planner_);
95 
96  return BT::NodeStatus::SUCCESS;
97 }
98 
99 void
100 PlannerSelector::callbackPlannerSelect(const std_msgs::msg::String::SharedPtr msg)
101 {
102  last_selected_planner_ = msg->data;
103 }
104 
105 } // namespace nav2_behavior_tree
106 
107 #include "behaviortree_cpp/bt_factory.h"
108 BT_REGISTER_NODES(factory)
109 {
110  factory.registerNodeType<nav2_behavior_tree::PlannerSelector>("PlannerSelector");
111 }
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.