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 "behaviortree_cpp/decorator_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav_msgs/msg/path.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 #include "rclcpp/rclcpp.hpp"
30 namespace nav2_behavior_tree
46 const std::string & name,
47 const BT::NodeConfiguration & conf);
56 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
59 BT::InputPort<nav_msgs::msg::Path>(
"path",
"Planned Path"),
60 BT::InputPort<double>(
62 "Proximity length (m) for the path to be longer on approach"),
63 BT::InputPort<double>(
65 "Length multiplication factor to check if the path is significantly longer"),
73 BT::NodeStatus
tick()
override;
83 nav_msgs::msg::Path & new_path,
84 nav_msgs::msg::Path & old_path);
92 bool isRobotInGoalProximity(
93 nav_msgs::msg::Path & old_path,
103 bool isNewPathLonger(
104 nav_msgs::msg::Path & new_path,
105 nav_msgs::msg::Path & old_path,
106 double & length_factor);
109 nav_msgs::msg::Path new_path_;
110 nav_msgs::msg::Path old_path_;
111 double prox_len_ = std::numeric_limits<double>::max();
112 double length_factor_ = std::numeric_limits<double>::max();
113 nav2::LifecycleNode::SharedPtr node_;
114 bool first_time_ =
true;
A BT::DecoratorNode that ticks its child every time when the length of the new path is smaller than t...
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.