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

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

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

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

Public Member 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: More...
 
void setPlan (const nav_msgs::msg::Path &path)
 Sets the global plan. More...
 
nav_msgs::msg::Path getPlan ()
 Gets the global plan. More...
 

Protected Attributes

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

Detailed Description

Handles input paths to transform them to local frames required.

Definition at line 31 of file path_handler.hpp.

Member Function Documentation

◆ getPlan()

nav_msgs::msg::Path nav2_graceful_controller::PathHandler::getPlan ( )
inline

Gets the global plan.

Returns
The global plan

Definition at line 71 of file path_handler.hpp.

◆ setPlan()

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

Sets the global plan.

Parameters
pathThe global plan

Definition at line 121 of file path_handler.cpp.

◆ transformGlobalPlan()

nav_msgs::msg::Path nav2_graceful_controller::PathHandler::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
    posepose to transform
    max_robot_pose_search_distDistance to search for matching nearest path point
    Returns
    Path in new frame

Definition at line 41 of file path_handler.cpp.


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