Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
goal_updater_node.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Francisco Martin Rico
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 "geometry_msgs/msg/pose_stamped.hpp"
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 {
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  std::string goal_updater_topic;
43  node_->get_parameter_or<std::string>("goal_updater_topic", goal_updater_topic, "goal_update");
44 
45  rclcpp::SubscriptionOptions sub_option;
46  sub_option.callback_group = callback_group_;
47  goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
48  goal_updater_topic,
49  rclcpp::SystemDefaultsQoS(),
50  std::bind(&GoalUpdater::callback_updated_goal, this, _1),
51  sub_option);
52 
53  // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
54  callback_group_executor_.spin_all(std::chrono::milliseconds(1));
55 }
56 
57 inline BT::NodeStatus GoalUpdater::tick()
58 {
59  geometry_msgs::msg::PoseStamped goal;
60 
61  getInput("input_goal", goal);
62 
63  callback_group_executor_.spin_all(std::chrono::milliseconds(49));
64 
65  if (last_goal_received_.header.stamp != rclcpp::Time(0)) {
66  auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
67  auto goal_time = rclcpp::Time(goal.header.stamp);
68  if (last_goal_received_time > goal_time) {
69  goal = last_goal_received_;
70  } else {
71  RCLCPP_WARN(
72  node_->get_logger(), "The timestamp of the received goal (%f) is older than the "
73  "current goal (%f). Ignoring the received goal.",
74  last_goal_received_time.seconds(), goal_time.seconds());
75  }
76  }
77 
78  setOutput("output_goal", goal);
79  return child_node_->executeTick();
80 }
81 
82 void
83 GoalUpdater::callback_updated_goal(const geometry_msgs::msg::PoseStamped::SharedPtr msg)
84 {
85  last_goal_received_ = *msg;
86 }
87 
88 } // namespace nav2_behavior_tree
89 
90 #include "behaviortree_cpp/bt_factory.h"
91 BT_REGISTER_NODES(factory)
92 {
93  factory.registerNodeType<nav2_behavior_tree::GoalUpdater>("GoalUpdater");
94 }
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.