19 #include "nav_msgs/msg/path.hpp"
20 #include "nav2_util/geometry_utils.hpp"
22 #include "nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp"
24 namespace nav2_behavior_tree
27 RemovePassedGoals::RemovePassedGoals(
28 const std::string & name,
29 const BT::NodeConfiguration & conf)
30 : BT::ActionNodeBase(name, conf),
31 viapoint_achieved_radius_(0.5)
33 getInput(
"radius", viapoint_achieved_radius_);
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_);
42 inline BT::NodeStatus RemovePassedGoals::tick()
44 setStatus(BT::NodeStatus::RUNNING);
47 getInput(
"input_goals", goal_poses);
49 if (goal_poses.empty()) {
50 setOutput(
"output_goals", goal_poses);
51 return BT::NodeStatus::SUCCESS;
54 using namespace nav2_util::geometry_utils;
56 geometry_msgs::msg::PoseStamped current_pose;
57 if (!nav2_util::getCurrentPose(
58 current_pose, *tf_, global_frame_, robot_base_frame_,
59 transform_tolerance_))
61 return BT::NodeStatus::FAILURE;
65 while (goal_poses.size() > 1) {
66 dist_to_goal = euclidean_distance(goal_poses[0].pose, current_pose.pose);
68 if (dist_to_goal > viapoint_achieved_radius_) {
72 goal_poses.erase(goal_poses.begin());
75 setOutput(
"output_goals", goal_poses);
77 return BT::NodeStatus::SUCCESS;
82 #include "behaviortree_cpp_v3/bt_factory.h"
83 BT_REGISTER_NODES(factory)