Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
goal_updater_node.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Francisco Martin Rico
3 // Copyright (c) 2024 Angsa Robotics
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 "behaviortree_cpp/decorator_node.h"
21 
22 #include "nav2_behavior_tree/plugins/decorator/goal_updater_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::DecoratorNode(name, conf),
35  goal_updater_topic_("goal_update"),
36  goals_updater_topic_("goals_update")
37 {
38  initialize();
39 
40  // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
41  callback_group_executor_.spin_all(std::chrono::milliseconds(1));
42 }
43 
44 void GoalUpdater::initialize()
45 {
46  createROSInterfaces();
47 }
48 
49 void GoalUpdater::createROSInterfaces()
50 {
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  std::string goal_updater_topic_new;
58  std::string goals_updater_topic_new;
59  node_->get_parameter_or<std::string>("goal_updater_topic", goal_updater_topic_new, "goal_update");
60  node_->get_parameter_or<std::string>("goals_updater_topic", goals_updater_topic_new,
61  "goals_update");
62 
63  // Only create a new subscriber if the topic has changed or subscriber is empty
64  if (goal_updater_topic_new != goal_updater_topic_ || !goal_sub_) {
65  goal_updater_topic_ = goal_updater_topic_new;
66  goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
67  goal_updater_topic_,
68  std::bind(&GoalUpdater::callback_updated_goal, this, _1),
70  callback_group_);
71  }
72  if (goals_updater_topic_new != goals_updater_topic_ || !goals_sub_) {
73  goals_updater_topic_ = goals_updater_topic_new;
74  goals_sub_ = node_->create_subscription<nav_msgs::msg::Goals>(
75  goals_updater_topic_,
76  std::bind(&GoalUpdater::callback_updated_goals, this, _1),
78  callback_group_);
79  }
80 }
81 
82 inline BT::NodeStatus GoalUpdater::tick()
83 {
84  if (!BT::isStatusActive(status())) {
85  initialize();
86  }
87 
88  geometry_msgs::msg::PoseStamped goal;
89  nav_msgs::msg::Goals goals;
90 
91  getInput("input_goal", goal);
92  getInput("input_goals", goals);
93 
94  callback_group_executor_.spin_all(std::chrono::milliseconds(49));
95 
96  if (last_goal_received_set_) {
97  if (last_goal_received_.header.stamp == rclcpp::Time(0)) {
98  // if the goal doesn't have a timestamp, we reject it
99  RCLCPP_WARN(
100  node_->get_logger(), "The received goal has no timestamp. Ignoring.");
101  setOutput("output_goal", goal);
102  } else {
103  auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
104  auto goal_time = rclcpp::Time(goal.header.stamp);
105  if (last_goal_received_time >= goal_time) {
106  setOutput("output_goal", last_goal_received_);
107  } else {
108  RCLCPP_INFO(
109  node_->get_logger(), "The timestamp of the received goal (%f) is older than the "
110  "current goal (%f). Ignoring the received goal.",
111  last_goal_received_time.seconds(), goal_time.seconds());
112  setOutput("output_goal", goal);
113  }
114  }
115  } else {
116  setOutput("output_goal", goal);
117  }
118 
119  if (last_goals_received_set_) {
120  if (last_goals_received_.goals.empty()) {
121  setOutput("output_goals", goals);
122  } else if (last_goals_received_.header.stamp == rclcpp::Time(0)) {
123  RCLCPP_WARN(
124  node_->get_logger(), "The received goals array has no timestamp. Ignoring.");
125  setOutput("output_goals", goals);
126  } else {
127  auto last_goals_received_time = rclcpp::Time(last_goals_received_.header.stamp);
128  auto goals_time = rclcpp::Time(goals.header.stamp);
129  if (last_goals_received_time >= goals_time) {
130  setOutput("output_goals", last_goals_received_);
131  } else {
132  RCLCPP_INFO(
133  node_->get_logger(), "The timestamp of the received goals (%f) is older than the "
134  "current goals (%f). Ignoring the received goals.",
135  last_goals_received_time.seconds(), goals_time.seconds());
136  setOutput("output_goals", goals);
137  }
138  }
139  } else {
140  setOutput("output_goals", goals);
141  }
142 
143  return child_node_->executeTick();
144 }
145 
146 void
147 GoalUpdater::callback_updated_goal(const geometry_msgs::msg::PoseStamped::SharedPtr msg)
148 {
149  last_goal_received_ = *msg;
150  last_goal_received_set_ = true;
151 }
152 
153 void
154 GoalUpdater::callback_updated_goals(const nav_msgs::msg::Goals::SharedPtr msg)
155 {
156  last_goals_received_ = *msg;
157  last_goals_received_set_ = true;
158 }
159 
160 } // namespace nav2_behavior_tree
161 
162 #include "behaviortree_cpp/bt_factory.h"
163 BT_REGISTER_NODES(factory)
164 {
165  factory.registerNodeType<nav2_behavior_tree::GoalUpdater>("GoalUpdater");
166 }
A QoS profile for standard reliable topics with a history of 10 messages.
A BT::DecoratorNode that subscribes to a goal topic and updates the current goal on the blackboard.
GoalUpdater(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::GoalUpdater.