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 "behaviortree_cpp/action_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav_msgs/msg/goals.hpp"
25 #include "nav2_behavior_tree/bt_utils.hpp"
26 #include "nav2_behavior_tree/json_utils.hpp"
27 #include "nav2_msgs/msg/waypoint_status.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_ros_common/lifecycle_node.hpp"
32 namespace nav2_behavior_tree
43 const std::string & xml_tag_name,
44 const BT::NodeConfiguration & conf);
51 static BT::PortsList providedPorts()
54 BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
55 BT::RegisterJsonDefinition<nav2_msgs::msg::WaypointStatus>();
56 BT::RegisterJsonDefinition<std::vector<nav2_msgs::msg::WaypointStatus>>();
59 BT::InputPort<nav_msgs::msg::Goals>(
"input_goals",
60 "Original goals to remove viapoints from"),
61 BT::OutputPort<nav_msgs::msg::Goals>(
"output_goals",
62 "Goals with passed viapoints removed"),
63 BT::InputPort<double>(
"radius", 0.5,
"radius to goal for it to be considered for removal"),
64 BT::InputPort<std::string>(
"robot_base_frame",
"Robot base frame"),
65 BT::InputPort<std::vector<nav2_msgs::msg::WaypointStatus>>(
"input_waypoint_statuses",
66 "Original waypoint_statuses to mark waypoint status from"),
67 BT::OutputPort<std::vector<nav2_msgs::msg::WaypointStatus>>(
"output_waypoint_statuses",
68 "Waypoint_statuses with passed waypoints marked")
73 void halt()
override {}
74 BT::NodeStatus tick()
override;
76 double viapoint_achieved_radius_;
77 double transform_tolerance_;
78 nav2::LifecycleNode::SharedPtr node_;
79 std::shared_ptr<tf2_ros::Buffer> tf_;
80 std::string robot_base_frame_;
A BT::ActionNodeBase that removes goals that the robot passed near to.
void initialize()
Function to read parameters and initialize class variables.