Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smoother_selector_node.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Pablo IƱigo Blasco
3 // Copyright (c) 2022 Owen Hooper
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include <string>
18 #include <memory>
19 
20 #include "std_msgs/msg/string.hpp"
21 
22 #include "nav2_behavior_tree/plugins/action/smoother_selector_node.hpp"
23 
24 #include "rclcpp/rclcpp.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
29 using std::placeholders::_1;
30 
32  const std::string & name,
33  const BT::NodeConfiguration & conf)
34 : BT::SyncActionNode(name, conf)
35 {
36  initialize();
37  bt_loop_duration_ =
38  config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
39 }
40 
41 void SmootherSelector::initialize()
42 {
43  createROSInterfaces();
44 }
45 
46 void SmootherSelector::createROSInterfaces()
47 {
48  std::string topic_new;
49  getInput("topic_name", topic_new);
50  if (topic_new != topic_name_ || !smoother_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,
55  false);
56  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 
58  smoother_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
59  topic_name_,
60  std::bind(&SmootherSelector::callbackSmootherSelect, this, _1),
62  callback_group_);
63  }
64 }
65 
66 BT::NodeStatus SmootherSelector::tick()
67 {
68  if (!BT::isStatusActive(status())) {
69  initialize();
70  }
71 
72  callback_group_executor_.spin_all(bt_loop_duration_);
73 
74  // This behavior always use the last selected smoother received from the topic input.
75  // When no input is specified it uses the default smoother.
76  // If the default smoother is not specified then we work in "required smoother mode":
77  // In this mode, the behavior returns failure if the smoother selection is not received from
78  // the topic input.
79  if (last_selected_smoother_.empty()) {
80  std::string default_smoother;
81  getInput("default_smoother", default_smoother);
82  if (default_smoother.empty()) {
83  return BT::NodeStatus::FAILURE;
84  } else {
85  last_selected_smoother_ = default_smoother;
86  }
87  }
88 
89  setOutput("selected_smoother", last_selected_smoother_);
90 
91  return BT::NodeStatus::SUCCESS;
92 }
93 
94 void
95 SmootherSelector::callbackSmootherSelect(const std_msgs::msg::String::SharedPtr msg)
96 {
97  last_selected_smoother_ = msg->data;
98 }
99 
100 } // namespace nav2_behavior_tree
101 
102 #include "behaviortree_cpp/bt_factory.h"
103 BT_REGISTER_NODES(factory)
104 {
105  factory.registerNodeType<nav2_behavior_tree::SmootherSelector>("SmootherSelector");
106 }
A QoS profile for latched, reliable topics with a history of 10 messages.
The SmootherSelector behavior is used to switch the smoother that will be used by the smoother server...
SmootherSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SmootherSelector.