Nav2 Navigation Stack - humble  humble
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_util/node_utils.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 #include "nav_2d_utils/tf_help.hpp"
25 #include "nav2_graceful_controller/path_handler.hpp"
26 #include "nav2_core/exceptions.hpp"
27 
28 namespace nav2_graceful_controller
29 {
30 
31 using nav2_util::geometry_utils::euclidean_distance;
32 
34  tf2::Duration 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_buffer_(tf), costmap_ros_(costmap_ros)
38 {
39 }
40 
42  const geometry_msgs::msg::PoseStamped & pose,
43  double max_robot_pose_search_dist)
44 {
45  // Check first if the plan is empty
46  if (global_plan_.poses.empty()) {
47  throw nav2_core::PlannerException("Received plan with zero length");
48  }
49 
50  // Let's get the pose of the robot in the frame of the plan
51  geometry_msgs::msg::PoseStamped robot_pose;
52  if (!nav_2d_utils::transformPose(
53  tf_buffer_, global_plan_.header.frame_id, pose, robot_pose,
54  transform_tolerance_))
55  {
56  throw nav2_core::PlannerException("Unable to transform robot pose into global plan's frame");
57  }
58 
59  // Find the first pose in the global plan that's further than max_robot_pose_search_dist
60  // from the robot using integrated distance
61  auto closest_pose_upper_bound =
62  nav2_util::geometry_utils::first_after_integrated_distance(
63  global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist);
64 
65  // First find the closest pose on the path to the robot
66  // bounded by when the path turns around (if it does) so we don't get a pose from a later
67  // portion of the path
68  auto transformation_begin =
69  nav2_util::geometry_utils::min_by(
70  global_plan_.poses.begin(), closest_pose_upper_bound,
71  [&robot_pose](const geometry_msgs::msg::PoseStamped & ps) {
72  return euclidean_distance(robot_pose, ps);
73  });
74 
75  // We'll discard points on the plan that are outside the local costmap
76  double dist_threshold = std::max(
77  costmap_ros_->getCostmap()->getSizeInMetersX(),
78  costmap_ros_->getCostmap()->getSizeInMetersY()) / 2.0;
79  auto transformation_end = std::find_if(
80  transformation_begin, global_plan_.poses.end(),
81  [&](const auto & global_plan_pose) {
82  return euclidean_distance(global_plan_pose, robot_pose) > dist_threshold;
83  });
84 
85  // Lambda to transform a PoseStamped from global frame to local
86  auto transformGlobalPoseToLocal = [&](const auto & global_plan_pose) {
87  geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
88  stamped_pose.header.frame_id = global_plan_.header.frame_id;
89  stamped_pose.header.stamp = robot_pose.header.stamp;
90  stamped_pose.pose = global_plan_pose.pose;
91  if (!nav_2d_utils::transformPose(
92  tf_buffer_, costmap_ros_->getBaseFrameID(), stamped_pose,
93  transformed_pose, transform_tolerance_))
94  {
95  throw nav2_core::PlannerException("Unable to transform plan pose into local frame");
96  }
97  transformed_pose.pose.position.z = 0.0;
98  return transformed_pose;
99  };
100 
101  // Transform the near part of the global plan into the robot's frame of reference.
102  nav_msgs::msg::Path transformed_plan;
103  transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
104  transformed_plan.header.stamp = robot_pose.header.stamp;
105  std::transform(
106  transformation_begin, transformation_end,
107  std::back_inserter(transformed_plan.poses),
108  transformGlobalPoseToLocal);
109 
110  // Remove the portion of the global plan that we've already passed so we don't
111  // process it on the next iteration (this is called path pruning)
112  global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
113 
114  if (transformed_plan.poses.empty()) {
115  throw nav2_core::PlannerException("Resulting plan has 0 poses in it.");
116  }
117 
118  return transformed_plan;
119 }
120 
121 void PathHandler::setPlan(const nav_msgs::msg::Path & path)
122 {
123  global_plan_ = path;
124 }
125 
126 } // namespace nav2_graceful_controller
void setPlan(const nav_msgs::msg::Path &path)
Sets the global plan.
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 ine...
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.