18 #include "nav2_util/geometry_utils.hpp"
20 #include "nav2_behavior_tree/plugins/decorator/path_longer_on_approach.hpp"
22 namespace nav2_behavior_tree
26 const std::string & name,
27 const BT::NodeConfiguration & conf)
28 : BT::DecoratorNode(name, conf)
30 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
33 bool PathLongerOnApproach::isPathUpdated(
34 nav_msgs::msg::Path & new_path,
35 nav_msgs::msg::Path & old_path)
37 return old_path.poses.size() != 0 &&
38 new_path.poses.size() != 0 &&
39 new_path.poses.size() != old_path.poses.size() &&
40 old_path.poses.back().pose.position == new_path.poses.back().pose.position;
43 bool PathLongerOnApproach::isRobotInGoalProximity(
44 nav_msgs::msg::Path & old_path,
47 return nav2_util::geometry_utils::calculate_path_length(old_path, 0) < prox_leng;
50 bool PathLongerOnApproach::isNewPathLonger(
51 nav_msgs::msg::Path & new_path,
52 nav_msgs::msg::Path & old_path,
53 double & length_factor)
55 return nav2_util::geometry_utils::calculate_path_length(new_path, 0) >
56 length_factor * nav2_util::geometry_utils::calculate_path_length(
62 getInput(
"path", new_path_);
63 getInput(
"prox_len", prox_len_);
64 getInput(
"length_factor", length_factor_);
66 if (first_time_ ==
false) {
67 if (old_path_.poses.empty() || new_path_.poses.empty() ||
68 old_path_.poses.back().pose != new_path_.poses.back().pose)
73 setStatus(BT::NodeStatus::RUNNING);
77 if (isPathUpdated(new_path_, old_path_) && isRobotInGoalProximity(old_path_, prox_len_) &&
78 isNewPathLonger(new_path_, old_path_, length_factor_) && !first_time_)
80 const BT::NodeStatus child_state = child_node_->executeTick();
81 switch (child_state) {
82 case BT::NodeStatus::SKIPPED:
83 case BT::NodeStatus::RUNNING:
85 case BT::NodeStatus::SUCCESS:
86 case BT::NodeStatus::FAILURE:
87 old_path_ = new_path_;
91 old_path_ = new_path_;
92 return BT::NodeStatus::FAILURE;
95 old_path_ = new_path_;
97 return BT::NodeStatus::SUCCESS;
102 #include "behaviortree_cpp/bt_factory.h"
103 BT_REGISTER_NODES(factory)
A BT::DecoratorNode that ticks its child every time when the length of the new path is smaller than t...
PathLongerOnApproach(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::PathLongerOnApproach.
BT::NodeStatus tick() override
The main override required by a BT action.