Class PathHandler

Class Documentation

class PathHandler

Handles input paths to transform them to local frames required.

Public Functions

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.

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 ineligible to be selected as a motion target point if they are any of the following:

  • Outside the local_costmap (collision avoidance cannot be assured)

Parameters:
  • pose – pose to transform

  • max_robot_pose_search_dist – Distance to search for matching nearest path point

Returns:

Path in new frame

void setPlan(const nav_msgs::msg::Path &path)

Sets the global plan.

Parameters:

path – The global plan

inline nav_msgs::msg::Path getPlan()

Gets the global plan.

Returns:

The global plan

Protected Attributes

rclcpp::Duration transform_tolerance_ = {0, 0}
std::shared_ptr<tf2_ros::Buffer> tf_buffer_
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
nav_msgs::msg::Path global_plan_
rclcpp::Logger logger_ = {rclcpp::get_logger("GracefulPathHandler")}