Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
remove_passed_goals_action.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_PASSED_GOALS_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_PASSED_GOALS_ACTION_HPP_
17 
18 #include <vector>
19 #include <memory>
20 #include <string>
21 
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 #include "behaviortree_cpp/action_node.h"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 
28 namespace nav2_behavior_tree
29 {
30 
31 class RemovePassedGoals : public BT::ActionNodeBase
32 {
33 public:
34  typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
35 
37  const std::string & xml_tag_name,
38  const BT::NodeConfiguration & conf);
39 
43  void initialize();
44 
45  static BT::PortsList providedPorts()
46  {
47  return {
48  BT::InputPort<Goals>("input_goals", "Original goals to remove viapoints from"),
49  BT::OutputPort<Goals>("output_goals", "Goals with passed viapoints removed"),
50  BT::InputPort<double>("radius", 0.5, "radius to goal for it to be considered for removal"),
51  BT::InputPort<std::string>("global_frame", "Global frame"),
52  BT::InputPort<std::string>("robot_base_frame", "Robot base frame"),
53  };
54  }
55 
56 private:
57  void halt() override {}
58  BT::NodeStatus tick() override;
59 
60  double viapoint_achieved_radius_;
61  double transform_tolerance_;
62  std::shared_ptr<tf2_ros::Buffer> tf_;
63  std::string robot_base_frame_;
64 };
65 
66 } // namespace nav2_behavior_tree
67 
68 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_PASSED_GOALS_ACTION_HPP_
void initialize()
Function to read parameters and initialize class variables.