Nav2 Navigation Stack - humble  humble
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  getInput("radius", viapoint_achieved_radius_);
34 
35  getInput("global_frame", global_frame_);
36  getInput("robot_base_frame", robot_base_frame_);
37  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
38  auto node = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
39  node->get_parameter("transform_tolerance", transform_tolerance_);
40 }
41 
42 inline BT::NodeStatus RemovePassedGoals::tick()
43 {
44  setStatus(BT::NodeStatus::RUNNING);
45 
46  Goals goal_poses;
47  getInput("input_goals", goal_poses);
48 
49  if (goal_poses.empty()) {
50  setOutput("output_goals", goal_poses);
51  return BT::NodeStatus::SUCCESS;
52  }
53 
54  using namespace nav2_util::geometry_utils; // NOLINT
55 
56  geometry_msgs::msg::PoseStamped current_pose;
57  if (!nav2_util::getCurrentPose(
58  current_pose, *tf_, global_frame_, robot_base_frame_,
59  transform_tolerance_))
60  {
61  return BT::NodeStatus::FAILURE;
62  }
63 
64  double dist_to_goal;
65  while (goal_poses.size() > 1) {
66  dist_to_goal = euclidean_distance(goal_poses[0].pose, current_pose.pose);
67 
68  if (dist_to_goal > viapoint_achieved_radius_) {
69  break;
70  }
71 
72  goal_poses.erase(goal_poses.begin());
73  }
74 
75  setOutput("output_goals", goal_poses);
76 
77  return BT::NodeStatus::SUCCESS;
78 }
79 
80 } // namespace nav2_behavior_tree
81 
82 #include "behaviortree_cpp_v3/bt_factory.h"
83 BT_REGISTER_NODES(factory)
84 {
85  factory.registerNodeType<nav2_behavior_tree::RemovePassedGoals>("RemovePassedGoals");
86 }