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)
34 void RemovePassedGoals::initialize()
36 getInput(
"radius", viapoint_achieved_radius_);
38 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
39 auto node = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
40 node->get_parameter(
"transform_tolerance", transform_tolerance_);
42 robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
43 node,
"robot_base_frame",
this);
46 inline BT::NodeStatus RemovePassedGoals::tick()
48 if (!BT::isStatusActive(status())) {
53 getInput(
"input_goals", goal_poses);
55 if (goal_poses.empty()) {
56 setOutput(
"output_goals", goal_poses);
57 return BT::NodeStatus::SUCCESS;
60 using namespace nav2_util::geometry_utils;
62 geometry_msgs::msg::PoseStamped current_pose;
63 if (!nav2_util::getCurrentPose(
64 current_pose, *tf_, goal_poses[0].header.frame_id, robot_base_frame_,
65 transform_tolerance_))
67 return BT::NodeStatus::FAILURE;
71 while (goal_poses.size() > 1) {
72 dist_to_goal = euclidean_distance(goal_poses[0].pose, current_pose.pose);
74 if (dist_to_goal > viapoint_achieved_radius_) {
78 goal_poses.erase(goal_poses.begin());
81 setOutput(
"output_goals", goal_poses);
83 return BT::NodeStatus::SUCCESS;
88 #include "behaviortree_cpp/bt_factory.h"
89 BT_REGISTER_NODES(factory)