Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
remove_passed_goals_action.cpp
1 // Copyright (c) 2021 Samsung Research America
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 #include <limits>
18 
19 #include "nav_msgs/msg/path.hpp"
20 #include "nav2_util/geometry_utils.hpp"
21 
22 #include "nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp"
23 
24 namespace nav2_behavior_tree
25 {
26 
27 RemovePassedGoals::RemovePassedGoals(
28  const std::string & name,
29  const BT::NodeConfiguration & conf)
30 : BT::ActionNodeBase(name, conf),
31  viapoint_achieved_radius_(0.5)
32 {}
33 
34 void RemovePassedGoals::initialize()
35 {
36  getInput("radius", viapoint_achieved_radius_);
37 
38  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
39  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
40  node_->get_parameter("transform_tolerance", transform_tolerance_);
41 
42  robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
43  node_, "robot_base_frame", this);
44 }
45 
46 inline BT::NodeStatus RemovePassedGoals::tick()
47 {
48  if (!BT::isStatusActive(status())) {
49  initialize();
50  }
51 
52  nav_msgs::msg::Goals goal_poses;
53  getInput("input_goals", goal_poses);
54 
55  if (goal_poses.goals.empty()) {
56  setOutput("output_goals", goal_poses);
57  return BT::NodeStatus::SUCCESS;
58  }
59 
60  using namespace nav2_util::geometry_utils; // NOLINT
61 
62  geometry_msgs::msg::PoseStamped current_pose;
63  if (!nav2_util::getCurrentPose(
64  current_pose, *tf_, goal_poses.goals[0].header.frame_id, robot_base_frame_,
65  transform_tolerance_))
66  {
67  return BT::NodeStatus::FAILURE;
68  }
69 
70  // get the `waypoint_statuses` vector
71  std::vector<nav2_msgs::msg::WaypointStatus> waypoint_statuses;
72  auto waypoint_statuses_get_res = getInput("input_waypoint_statuses", waypoint_statuses);
73  if (!waypoint_statuses_get_res) {
74  RCLCPP_ERROR_ONCE(node_->get_logger(), "Missing [input_waypoint_statuses] port input!");
75  }
76 
77  double dist_to_goal;
78  while (goal_poses.goals.size() > 1) {
79  dist_to_goal = euclidean_distance(goal_poses.goals[0].pose, current_pose.pose);
80 
81  if (dist_to_goal > viapoint_achieved_radius_) {
82  break;
83  }
84 
85  // mark waypoint statuses before the goal is erased from goals
86  if (waypoint_statuses_get_res) {
87  auto cur_waypoint_index =
88  find_next_matching_goal_in_waypoint_statuses(waypoint_statuses, goal_poses.goals[0]);
89  if (cur_waypoint_index == -1) {
90  RCLCPP_ERROR_ONCE(node_->get_logger(), "Failed to find matching goal in waypoint_statuses");
91  return BT::NodeStatus::FAILURE;
92  }
93  waypoint_statuses[cur_waypoint_index].waypoint_status =
94  nav2_msgs::msg::WaypointStatus::COMPLETED;
95  }
96 
97  goal_poses.goals.erase(goal_poses.goals.begin());
98  }
99 
100  setOutput("output_goals", goal_poses);
101  // set `waypoint_statuses` output
102  setOutput("output_waypoint_statuses", waypoint_statuses);
103 
104  return BT::NodeStatus::SUCCESS;
105 }
106 
107 } // namespace nav2_behavior_tree
108 
109 #include "behaviortree_cpp/bt_factory.h"
110 BT_REGISTER_NODES(factory)
111 {
112  factory.registerNodeType<nav2_behavior_tree::RemovePassedGoals>("RemovePassedGoals");
113 }
A BT::ActionNodeBase that removes goals that the robot passed near to.