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 
38  // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
39  callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
40 }
41 
42 void SmootherSelector::initialize()
43 {
44  createROSInterfaces();
45 }
46 
47 void SmootherSelector::createROSInterfaces()
48 {
49  std::string topic_new;
50  getInput("topic_name", topic_new);
51  if (topic_new != topic_name_ || !smoother_selector_sub_) {
52  topic_name_ = topic_new;
53  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
54  callback_group_ = node_->create_callback_group(
55  rclcpp::CallbackGroupType::MutuallyExclusive,
56  false);
57  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
58 
59  smoother_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
60  topic_name_,
61  std::bind(&SmootherSelector::callbackSmootherSelect, this, _1),
63  callback_group_);
64  }
65 }
66 
67 BT::NodeStatus SmootherSelector::tick()
68 {
69  if (!BT::isStatusActive(status())) {
70  initialize();
71  }
72 
73  callback_group_executor_.spin_some();
74 
75  // This behavior always use the last selected smoother received from the topic input.
76  // When no input is specified it uses the default smoother.
77  // If the default smoother is not specified then we work in "required smoother mode":
78  // In this mode, the behavior returns failure if the smoother selection is not received from
79  // the topic input.
80  if (last_selected_smoother_.empty()) {
81  std::string default_smoother;
82  getInput("default_smoother", default_smoother);
83  if (default_smoother.empty()) {
84  return BT::NodeStatus::FAILURE;
85  } else {
86  last_selected_smoother_ = default_smoother;
87  }
88  }
89 
90  setOutput("selected_smoother", last_selected_smoother_);
91 
92  return BT::NodeStatus::SUCCESS;
93 }
94 
95 void
96 SmootherSelector::callbackSmootherSelect(const std_msgs::msg::String::SharedPtr msg)
97 {
98  last_selected_smoother_ = msg->data;
99 }
100 
101 } // namespace nav2_behavior_tree
102 
103 #include "behaviortree_cpp/bt_factory.h"
104 BT_REGISTER_NODES(factory)
105 {
106  factory.registerNodeType<nav2_behavior_tree::SmootherSelector>("SmootherSelector");
107 }
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.