Nav2 Navigation Stack - humble  humble
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  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
37  callback_group_ = node_->create_callback_group(
38  rclcpp::CallbackGroupType::MutuallyExclusive,
39  false);
40  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
41 
42  getInput("topic_name", topic_name_);
43 
44  rclcpp::QoS qos(rclcpp::KeepLast(1));
45  qos.transient_local().reliable();
46 
47  rclcpp::SubscriptionOptions sub_option;
48  sub_option.callback_group = callback_group_;
49  smoother_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
50  topic_name_,
51  qos,
52  std::bind(&SmootherSelector::callbackSmootherSelect, this, _1),
53  sub_option);
54 }
55 
56 BT::NodeStatus SmootherSelector::tick()
57 {
58  callback_group_executor_.spin_some();
59 
60  // This behavior always use the last selected smoother received from the topic input.
61  // When no input is specified it uses the default smoother.
62  // If the default smoother is not specified then we work in "required smoother mode":
63  // In this mode, the behavior returns failure if the smoother selection is not received from
64  // the topic input.
65  if (last_selected_smoother_.empty()) {
66  std::string default_smoother;
67  getInput("default_smoother", default_smoother);
68  if (default_smoother.empty()) {
69  return BT::NodeStatus::FAILURE;
70  } else {
71  last_selected_smoother_ = default_smoother;
72  }
73  }
74 
75  setOutput("selected_smoother", last_selected_smoother_);
76 
77  return BT::NodeStatus::SUCCESS;
78 }
79 
80 void
81 SmootherSelector::callbackSmootherSelect(const std_msgs::msg::String::SharedPtr msg)
82 {
83  last_selected_smoother_ = msg->data;
84 }
85 
86 } // namespace nav2_behavior_tree
87 
88 #include "behaviortree_cpp_v3/bt_factory.h"
89 BT_REGISTER_NODES(factory)
90 {
91  factory.registerNodeType<nav2_behavior_tree::SmootherSelector>("SmootherSelector");
92 }
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.