Nav2 Navigation Stack - jazzy  jazzy
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_util/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 
27 namespace nav2_regulated_pure_pursuit_controller
28 {
29 
30 using nav2_util::geometry_utils::euclidean_distance;
31 
33  tf2::Duration transform_tolerance,
34  std::shared_ptr<tf2_ros::Buffer> tf,
35  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
36 : transform_tolerance_(transform_tolerance), tf_(tf), costmap_ros_(costmap_ros)
37 {
38 }
39 
41 {
42  const double max_costmap_dim_meters = std::max(
43  costmap_ros_->getCostmap()->getSizeInMetersX(),
44  costmap_ros_->getCostmap()->getSizeInMetersY());
45  return max_costmap_dim_meters / 2.0;
46 }
47 
49  const geometry_msgs::msg::PoseStamped & pose,
50  double max_robot_pose_search_dist,
51  bool reject_unit_path)
52 {
53  if (global_plan_.poses.empty()) {
54  throw nav2_core::InvalidPath("Received plan with zero length");
55  }
56 
57  if (reject_unit_path && global_plan_.poses.size() == 1) {
58  throw nav2_core::InvalidPath("Received plan with length of one");
59  }
60 
61  // let's get the pose of the robot in the frame of the plan
62  geometry_msgs::msg::PoseStamped robot_pose;
63  if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
64  throw nav2_core::ControllerTFError("Unable to transform robot pose into global plan's frame");
65  }
66 
67  auto closest_pose_upper_bound =
68  nav2_util::geometry_utils::first_after_integrated_distance(
69  global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist);
70 
71  // First find the closest pose on the path to the robot
72  // bounded by when the path turns around (if it does) so we don't get a pose from a later
73  // portion of the path
74  auto transformation_begin =
75  nav2_util::geometry_utils::min_by(
76  global_plan_.poses.begin(), closest_pose_upper_bound,
77  [&robot_pose](const geometry_msgs::msg::PoseStamped & ps) {
78  return euclidean_distance(robot_pose, ps);
79  });
80 
81  // Make sure we always have at least 2 points on the transformed plan and that we don't prune
82  // the global plan below 2 points in order to have always enough point to interpolate the
83  // end of path direction
84  if (global_plan_.poses.begin() != closest_pose_upper_bound && global_plan_.poses.size() > 1 &&
85  transformation_begin == std::prev(closest_pose_upper_bound))
86  {
87  transformation_begin = std::prev(std::prev(closest_pose_upper_bound));
88  }
89 
90  // We'll discard points on the plan that are outside the local costmap
91  const double max_costmap_extent = getCostmapMaxExtent();
92  auto transformation_end = std::find_if(
93  transformation_begin, global_plan_.poses.end(),
94  [&](const auto & global_plan_pose) {
95  return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
96  });
97 
98  // Lambda to transform a PoseStamped from global frame to local
99  auto transformGlobalPoseToLocal = [&](const auto & global_plan_pose) {
100  geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
101  stamped_pose.header.frame_id = global_plan_.header.frame_id;
102  stamped_pose.header.stamp = robot_pose.header.stamp;
103  stamped_pose.pose = global_plan_pose.pose;
104  if (!transformPose(costmap_ros_->getBaseFrameID(), stamped_pose, transformed_pose)) {
105  throw nav2_core::ControllerTFError("Unable to transform plan pose into local frame");
106  }
107  transformed_pose.pose.position.z = 0.0;
108  return transformed_pose;
109  };
110 
111  // Transform the near part of the global plan into the robot's frame of reference.
112  nav_msgs::msg::Path transformed_plan;
113  std::transform(
114  transformation_begin, transformation_end,
115  std::back_inserter(transformed_plan.poses),
116  transformGlobalPoseToLocal);
117  transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
118  transformed_plan.header.stamp = robot_pose.header.stamp;
119 
120  // Remove the portion of the global plan that we've already passed so we don't
121  // process it on the next iteration (this is called path pruning)
122  global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
123 
124  if (transformed_plan.poses.empty()) {
125  throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
126  }
127 
128  return transformed_plan;
129 }
130 
132  const std::string frame,
133  const geometry_msgs::msg::PoseStamped & in_pose,
134  geometry_msgs::msg::PoseStamped & out_pose) const
135 {
136  if (in_pose.header.frame_id == frame) {
137  out_pose = in_pose;
138  return true;
139  }
140 
141  try {
142  tf_->transform(in_pose, out_pose, frame, transform_tolerance_);
143  out_pose.header.frame_id = frame;
144  return true;
145  } catch (tf2::TransformException & ex) {
146  RCLCPP_ERROR(logger_, "Exception in transformPose: %s", ex.what());
147  }
148  return false;
149 }
150 
151 } // namespace nav2_regulated_pure_pursuit_controller
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.
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...
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.