15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__PATH_LONGER_ON_APPROACH_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__PATH_LONGER_ON_APPROACH_HPP_
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "nav_msgs/msg/path.hpp"
24 #include "behaviortree_cpp_v3/decorator_node.h"
25 #include "rclcpp/rclcpp.hpp"
27 namespace nav2_behavior_tree
43 const std::string & name,
44 const BT::NodeConfiguration & conf);
53 BT::InputPort<nav_msgs::msg::Path>(
"path",
"Planned Path"),
54 BT::InputPort<double>(
56 "Proximity length (m) for the path to be longer on approach"),
57 BT::InputPort<double>(
59 "Length multiplication factor to check if the path is significantly longer"),
67 BT::NodeStatus
tick()
override;
77 nav_msgs::msg::Path & new_path,
78 nav_msgs::msg::Path & old_path);
86 bool isRobotInGoalProximity(
87 nav_msgs::msg::Path & old_path,
98 nav_msgs::msg::Path & new_path,
99 nav_msgs::msg::Path & old_path,
100 double & length_factor);
103 nav_msgs::msg::Path new_path_;
104 nav_msgs::msg::Path old_path_;
105 double prox_len_ = std::numeric_limits<double>::max();
106 double length_factor_ = std::numeric_limits<double>::max();
107 rclcpp::Node::SharedPtr node_;
108 bool first_time_ =
true;
A BT::DecoratorNode that ticks its child everytime when the length of the new path is smaller than th...
static BT::PortsList providedPorts()
Creates list of BT ports.
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.