Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_regulated_pure_pursuit_controller::PathHandler Class Reference

Handles input paths to transform them to local frames required. More...

#include <nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp>

Collaboration diagram for nav2_regulated_pure_pursuit_controller::PathHandler:
Collaboration graph
[legend]

Public Member Functions

 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.
 
 ~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: More...
 
void setPlan (const nav_msgs::msg::Path &path)
 
nav_msgs::msg::Path getPlan ()
 

Protected Member Functions

double getCostmapMaxExtent () const
 

Protected Attributes

rclcpp::Logger logger_ {rclcpp::get_logger("RPPPathHandler")}
 
double transform_tolerance_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROScostmap_ros_
 
nav_msgs::msg::Path global_plan_
 

Detailed Description

Handles input paths to transform them to local frames required.

Definition at line 39 of file path_handler.hpp.

Member Function Documentation

◆ getCostmapMaxExtent()

double nav2_regulated_pure_pursuit_controller::PathHandler::getCostmapMaxExtent ( ) const
protected

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

Returns
max of distance from center in meters to edge of costmap

Definition at line 41 of file path_handler.cpp.

Referenced by transformGlobalPlan().

Here is the caller graph for this function:

◆ transformGlobalPlan()

nav_msgs::msg::Path nav2_regulated_pure_pursuit_controller::PathHandler::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
    posepose to transform
    max_robot_pose_search_distDistance to search for matching nearest path point
    reject_unit_pathIf true, fail if path has only one pose
    Returns
    Path in new frame

Definition at line 49 of file path_handler.cpp.

References getCostmapMaxExtent().

Here is the call graph for this function:

The documentation for this class was generated from the following files: