Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
path_handler.cpp
1 // Copyright (c) 2022 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <algorithm>
16 #include <string>
17 #include <limits>
18 #include <memory>
19 #include <vector>
20 #include <utility>
21 
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"
27 
28 namespace nav2_regulated_pure_pursuit_controller
29 {
30 
31 using nav2_util::geometry_utils::euclidean_distance;
32 
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)
38 {
39 }
40 
42 {
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;
47 }
48 
50  const geometry_msgs::msg::PoseStamped & pose,
51  double max_robot_pose_search_dist,
52  bool reject_unit_path)
53 {
54  if (global_plan_.poses.empty()) {
55  throw nav2_core::InvalidPath("Received plan with zero length");
56  }
57 
58  if (reject_unit_path && global_plan_.poses.size() == 1) {
59  throw nav2_core::InvalidPath("Received plan with length of one");
60  }
61 
62  // let's get the pose of the robot in the frame of the plan
63  geometry_msgs::msg::PoseStamped robot_pose;
64  if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_, global_plan_.header.frame_id,
65  transform_tolerance_))
66  {
67  throw nav2_core::ControllerTFError("Unable to transform robot pose into global plan's frame");
68  }
69 
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);
73 
74  // First find the closest pose on the path to the robot
75  // bounded by when the path turns around (if it does) so we don't get a pose from a later
76  // portion of the path
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);
82  });
83 
84  // Make sure we always have at least 2 points on the transformed plan and that we don't prune
85  // the global plan below 2 points in order to have always enough point to interpolate the
86  // end of path direction
87  if (global_plan_.poses.begin() != closest_pose_upper_bound && global_plan_.poses.size() > 1 &&
88  transformation_begin == std::prev(closest_pose_upper_bound))
89  {
90  transformation_begin = std::prev(std::prev(closest_pose_upper_bound));
91  }
92 
93  // We'll discard points on the plan that are outside the local costmap
94  const double max_costmap_extent = getCostmapMaxExtent();
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;
99  });
100 
101  // Lambda to transform a PoseStamped from global frame to local
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_))
109  {
110  throw nav2_core::ControllerTFError("Unable to transform plan pose into local frame");
111  }
112  transformed_pose.pose.position.z = 0.0;
113  return transformed_pose;
114  };
115 
116  // Transform the near part of the global plan into the robot's frame of reference.
117  nav_msgs::msg::Path transformed_plan;
118  std::transform(
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;
124 
125  // Remove the portion of the global plan that we've already passed so we don't
126  // process it on the next iteration (this is called path pruning)
127  global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
128 
129  if (transformed_plan.poses.empty()) {
130  throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
131  }
132 
133  return transformed_plan;
134 }
135 
136 } // namespace nav2_regulated_pure_pursuit_controller
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...