22 #include "nav2_regulated_pure_pursuit_controller/path_handler.hpp"
23 #include "nav2_core/controller_exceptions.hpp"
24 #include "nav2_ros_common/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_util/robot_utils.hpp"
28 namespace nav2_regulated_pure_pursuit_controller
31 using nav2_util::geometry_utils::euclidean_distance;
34 double transform_tolerance,
35 std::shared_ptr<tf2_ros::Buffer> tf,
36 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
37 : transform_tolerance_(transform_tolerance), tf_(tf), costmap_ros_(costmap_ros)
43 const double max_costmap_dim_meters = std::max(
44 costmap_ros_->getCostmap()->getSizeInMetersX(),
45 costmap_ros_->getCostmap()->getSizeInMetersY());
46 return max_costmap_dim_meters / 2.0;
50 const geometry_msgs::msg::PoseStamped & pose,
51 double max_robot_pose_search_dist,
52 bool reject_unit_path)
54 if (global_plan_.poses.empty()) {
58 if (reject_unit_path && global_plan_.poses.size() == 1) {
63 geometry_msgs::msg::PoseStamped robot_pose;
64 if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_, global_plan_.header.frame_id,
65 transform_tolerance_))
70 auto closest_pose_upper_bound =
71 nav2_util::geometry_utils::first_after_integrated_distance(
72 global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist);
77 auto transformation_begin =
78 nav2_util::geometry_utils::min_by(
79 global_plan_.poses.begin(), closest_pose_upper_bound,
80 [&robot_pose](
const geometry_msgs::msg::PoseStamped & ps) {
81 return euclidean_distance(robot_pose, ps);
87 if (global_plan_.poses.begin() != closest_pose_upper_bound && global_plan_.poses.size() > 1 &&
88 transformation_begin == std::prev(closest_pose_upper_bound))
90 transformation_begin = std::prev(std::prev(closest_pose_upper_bound));
95 auto transformation_end = std::find_if(
96 transformation_begin, global_plan_.poses.end(),
97 [&](
const auto & global_plan_pose) {
98 return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
102 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
103 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
104 stamped_pose.header.frame_id = global_plan_.header.frame_id;
105 stamped_pose.header.stamp = robot_pose.header.stamp;
106 stamped_pose.pose = global_plan_pose.pose;
107 if (!nav2_util::transformPoseInTargetFrame(stamped_pose, transformed_pose, *tf_,
108 costmap_ros_->getBaseFrameID(), transform_tolerance_))
112 transformed_pose.pose.position.z = 0.0;
113 return transformed_pose;
117 nav_msgs::msg::Path transformed_plan;
119 transformation_begin, transformation_end,
120 std::back_inserter(transformed_plan.poses),
121 transformGlobalPoseToLocal);
122 transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
123 transformed_plan.header.stamp = robot_pose.header.stamp;
127 global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
129 if (transformed_plan.poses.empty()) {
133 return transformed_plan;
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.
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 i...
double getCostmapMaxExtent() const