Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
goal_checker_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/goal_checker_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  bt_loop_duration_ =
37  config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
38 }
39 
40 void GoalCheckerSelector::initialize()
41 {
42  createROSInterfaces();
43 }
44 
45 void GoalCheckerSelector::createROSInterfaces()
46 {
47  std::string topic_new;
48  getInput("topic_name", topic_new);
49  if (topic_new != topic_name_ || !goal_checker_selector_sub_) {
50  topic_name_ = topic_new;
51  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
52  callback_group_ = node_->create_callback_group(
53  rclcpp::CallbackGroupType::MutuallyExclusive,
54  false);
55  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
56 
57  goal_checker_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
58  topic_name_,
59  std::bind(&GoalCheckerSelector::callbackGoalCheckerSelect, this, _1),
61  callback_group_);
62  }
63 }
64 
65 BT::NodeStatus GoalCheckerSelector::tick()
66 {
67  if (!BT::isStatusActive(status())) {
68  initialize();
69  }
70 
71  callback_group_executor_.spin_all(bt_loop_duration_);
72 
73  // This behavior always use the last selected goal checker received from the topic input.
74  // When no input is specified it uses the default goal checker.
75  // If the default goal checker is not specified then we work in "required goal checker mode":
76  // In this mode, the behavior returns failure if the goal checker selection is not received from
77  // the topic input.
78  if (last_selected_goal_checker_.empty()) {
79  std::string default_goal_checker;
80  getInput("default_goal_checker", default_goal_checker);
81  if (default_goal_checker.empty()) {
82  return BT::NodeStatus::FAILURE;
83  } else {
84  last_selected_goal_checker_ = default_goal_checker;
85  }
86  }
87 
88  setOutput("selected_goal_checker", last_selected_goal_checker_);
89 
90  return BT::NodeStatus::SUCCESS;
91 }
92 
93 void
94 GoalCheckerSelector::callbackGoalCheckerSelect(const std_msgs::msg::String::SharedPtr msg)
95 {
96  last_selected_goal_checker_ = msg->data;
97 }
98 
99 } // namespace nav2_behavior_tree
100 
101 #include "behaviortree_cpp/bt_factory.h"
102 BT_REGISTER_NODES(factory)
103 {
104  factory.registerNodeType<nav2_behavior_tree::GoalCheckerSelector>("GoalCheckerSelector");
105 }
A QoS profile for latched, reliable topics with a history of 10 messages.
The GoalCheckerSelector behavior is used to switch the goal checker of the controller server....
GoalCheckerSelector(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::GoalCheckerSelector.