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