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/action_node.h"
26 #include "nav2_behavior_tree/bt_utils.hpp"
28 namespace nav2_behavior_tree
34 typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
37 const std::string & xml_tag_name,
38 const BT::NodeConfiguration & conf);
45 static BT::PortsList providedPorts()
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"),
57 void halt()
override {}
58 BT::NodeStatus tick()
override;
60 double viapoint_achieved_radius_;
61 double transform_tolerance_;
62 std::shared_ptr<tf2_ros::Buffer> tf_;
63 std::string robot_base_frame_;
void initialize()
Function to read parameters and initialize class variables.