15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_PASSED_GOALS_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_PASSED_GOALS_ACTION_HPP_
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_v3/action_node.h"
27 namespace nav2_behavior_tree
33 typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
36 const std::string & xml_tag_name,
37 const BT::NodeConfiguration & conf);
40 static BT::PortsList providedPorts()
43 BT::InputPort<Goals>(
"input_goals",
"Original goals to remove viapoints from"),
44 BT::OutputPort<Goals>(
"output_goals",
"Goals with passed viapoints removed"),
45 BT::InputPort<double>(
"radius", 0.5,
"radius to goal for it to be considered for removal"),
46 BT::InputPort<std::string>(
"global_frame", std::string(
"map"),
"Global frame"),
47 BT::InputPort<std::string>(
"robot_base_frame", std::string(
"base_link"),
"Robot base frame"),
52 void halt()
override {}
53 BT::NodeStatus tick()
override;
55 double viapoint_achieved_radius_;
56 std::string robot_base_frame_, global_frame_;
57 double transform_tolerance_;
58 std::shared_ptr<tf2_ros::Buffer> tf_;