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_regulated_pure_pursuit_controller::PathHandler.

~PathHandler() = default

Destrructor 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 ineligible to be selected as a lookahead 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

  • reject_unit_path – If true, fail if path has only one pose

Returns:

Path in new frame

bool transformPose(const std::string frame, const geometry_msgs::msg::PoseStamped &in_pose, geometry_msgs::msg::PoseStamped &out_pose) const

Transform a pose to another frame.

Parameters:
  • frame – Frame ID to transform to

  • in_pose – Pose input to transform

  • out_pose – transformed output

Returns:

bool if successful

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

Protected Functions

double getCostmapMaxExtent() const

Get the greatest extent of the costmap in meters from the center.

Returns:

max of distance from center in meters to edge of costmap

Protected Attributes

rclcpp::Logger logger_ = {rclcpp::get_logger("RPPPathHandler")}
tf2::Duration transform_tolerance_
std::shared_ptr<tf2_ros::Buffer> tf_
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
nav_msgs::msg::Path global_plan_