Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Handles input paths to transform them to local frames required. More...
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_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... | |
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. 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")} |
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_ |
Handles input paths to transform them to local frames required.
Definition at line 39 of file path_handler.hpp.
|
protected |
Get the greatest extent of the costmap in meters from the center.
Definition at line 40 of file path_handler.cpp.
Referenced by 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:
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 |
Definition at line 48 of file path_handler.cpp.
References getCostmapMaxExtent(), and transformPose().
bool nav2_regulated_pure_pursuit_controller::PathHandler::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.
frame | Frame ID to transform to |
in_pose | Pose input to transform |
out_pose | transformed output |
Definition at line 131 of file path_handler.cpp.
Referenced by transformGlobalPlan().