15 #ifndef NAV2_GRACEFUL_CONTROLLER__PATH_HANDLER_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__PATH_HANDLER_HPP_
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 #include "nav2_util/geometry_utils.hpp"
24 namespace nav2_graceful_controller
38 tf2::Duration transform_tolerance,
39 std::shared_ptr<tf2_ros::Buffer> tf,
40 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
56 const geometry_msgs::msg::PoseStamped & pose,
57 double max_robot_pose_search_dist);
64 void setPlan(
const nav_msgs::msg::Path & path);
71 nav_msgs::msg::Path
getPlan() {
return global_plan_;}
74 rclcpp::Duration transform_tolerance_{0, 0};
75 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
76 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
77 nav_msgs::msg::Path global_plan_;
78 rclcpp::Logger logger_ {rclcpp::get_logger(
"GracefulPathHandler")};
Handles input paths to transform them to local frames required.
nav_msgs::msg::Path getPlan()
Gets the global plan.
void setPlan(const nav_msgs::msg::Path &path)
Sets the global plan.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist)
Transforms global plan into same frame as pose and clips poses ineligible for motionTarget Points ine...
PathHandler(tf2::Duration transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_graceful_controller::PathHandler.
~PathHandler()=default
Destructor for nav2_graceful_controller::PathHandler.