15 #ifndef NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
16 #define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
24 #include "nav2_ros_common/lifecycle_node.hpp"
25 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
26 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
27 #include "nav2_util/odometry_utils.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_core/controller_exceptions.hpp"
30 #include "geometry_msgs/msg/pose.hpp"
32 namespace nav2_regulated_pure_pursuit_controller
46 double transform_tolerance,
47 std::shared_ptr<tf2_ros::Buffer> tf,
48 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
65 const geometry_msgs::msg::PoseStamped & pose,
66 double max_robot_pose_search_dist,
bool reject_unit_path =
false);
68 void setPlan(
const nav_msgs::msg::Path & path) {global_plan_ = path;}
70 nav_msgs::msg::Path getPlan() {
return global_plan_;}
79 rclcpp::Logger logger_ {rclcpp::get_logger(
"RPPPathHandler")};
80 double transform_tolerance_;
81 std::shared_ptr<tf2_ros::Buffer> tf_;
82 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
83 nav_msgs::msg::Path global_plan_;
Handles input paths to transform them to local frames required.
PathHandler(double transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_regulated_pure_pursuit_controller::PathHandler.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist, bool reject_unit_path=false)
Transforms global plan into same frame as pose and clips poses ineligible for lookaheadPoint Points i...
double getCostmapMaxExtent() const
~PathHandler()=default
Destrructor for nav2_regulated_pure_pursuit_controller::PathHandler.