Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
path_handler.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 // Copyright (c) 2023 Dexory
3 // Copyright (c) 2023 Open Navigation LLC
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include "nav2_mppi_controller/tools/path_handler.hpp"
18 #include "nav2_mppi_controller/tools/utils.hpp"
19 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
20 #include "nav2_util/robot_utils.hpp"
21 
22 namespace mppi
23 {
24 
26  nav2::LifecycleNode::WeakPtr parent, const std::string & name,
27  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
28  std::shared_ptr<tf2_ros::Buffer> buffer, ParametersHandler * param_handler)
29 {
30  name_ = name;
31  costmap_ = costmap;
32  tf_buffer_ = buffer;
33  auto node = parent.lock();
34  logger_ = node->get_logger();
35  parameters_handler_ = param_handler;
36 
37  auto getParam = parameters_handler_->getParamGetter(name_);
38  getParam(max_robot_pose_search_dist_, "max_robot_pose_search_dist", getMaxCostmapDist());
39  getParam(prune_distance_, "prune_distance", 1.5);
40  getParam(transform_tolerance_, "transform_tolerance", 0.1);
41  getParam(enforce_path_inversion_, "enforce_path_inversion", false);
42  if (enforce_path_inversion_) {
43  getParam(inversion_xy_tolerance_, "inversion_xy_tolerance", 0.2);
44  getParam(inversion_yaw_tolerance, "inversion_yaw_tolerance", 0.4);
45  inversion_locale_ = 0u;
46  }
47 }
48 
49 std::pair<nav_msgs::msg::Path, PathIterator>
51  const geometry_msgs::msg::PoseStamped & global_pose)
52 {
53  using nav2_util::geometry_utils::euclidean_distance;
54 
55  auto begin = global_plan_up_to_inversion_.poses.begin();
56 
57  // Limit the search for the closest pose up to max_robot_pose_search_dist on the path
58  auto closest_pose_upper_bound =
59  nav2_util::geometry_utils::first_after_integrated_distance(
60  global_plan_up_to_inversion_.poses.begin(), global_plan_up_to_inversion_.poses.end(),
61  max_robot_pose_search_dist_);
62 
63  // Find closest point to the robot
64  auto closest_point = nav2_util::geometry_utils::min_by(
65  begin, closest_pose_upper_bound,
66  [&global_pose](const geometry_msgs::msg::PoseStamped & ps) {
67  return euclidean_distance(global_pose, ps);
68  });
69 
70  nav_msgs::msg::Path transformed_plan;
71  transformed_plan.header.frame_id = costmap_->getGlobalFrameID();
72  transformed_plan.header.stamp = global_pose.header.stamp;
73 
74  auto pruned_plan_end =
75  nav2_util::geometry_utils::first_after_integrated_distance(
76  closest_point, global_plan_up_to_inversion_.poses.end(), prune_distance_);
77 
78  unsigned int mx, my;
79  // Find the furthest relevant pose on the path to consider within costmap
80  // bounds
81  // Transforming it to the costmap frame in the same loop
82  for (auto global_plan_pose = closest_point; global_plan_pose != pruned_plan_end;
83  ++global_plan_pose)
84  {
85  // Transform from global plan frame to costmap frame
86  geometry_msgs::msg::PoseStamped costmap_plan_pose;
87  global_plan_pose->header.stamp = global_pose.header.stamp;
88  global_plan_pose->header.frame_id = global_plan_.header.frame_id;
89  nav2_util::transformPoseInTargetFrame(*global_plan_pose, costmap_plan_pose, *tf_buffer_,
90  costmap_->getGlobalFrameID(), transform_tolerance_);
91 
92  // Check if pose is inside the costmap
93  if (!costmap_->getCostmap()->worldToMap(
94  costmap_plan_pose.pose.position.x, costmap_plan_pose.pose.position.y, mx, my))
95  {
96  return {transformed_plan, closest_point};
97  }
98 
99  // Filling the transformed plan to return with the transformed pose
100  transformed_plan.poses.push_back(costmap_plan_pose);
101  }
102 
103  return {transformed_plan, closest_point};
104 }
105 
106 geometry_msgs::msg::PoseStamped PathHandler::transformToGlobalPlanFrame(
107  const geometry_msgs::msg::PoseStamped & pose)
108 {
109  if (global_plan_up_to_inversion_.poses.empty()) {
110  throw nav2_core::InvalidPath("Received plan with zero length");
111  }
112 
113  geometry_msgs::msg::PoseStamped robot_pose;
114  if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_buffer_,
115  global_plan_up_to_inversion_.header.frame_id, transform_tolerance_))
116  {
118  "Unable to transform robot pose into global plan's frame");
119  }
120 
121  return robot_pose;
122 }
123 
124 nav_msgs::msg::Path PathHandler::transformPath(
125  const geometry_msgs::msg::PoseStamped & robot_pose)
126 {
127  // Find relevant bounds of path to use
128  geometry_msgs::msg::PoseStamped global_pose =
129  transformToGlobalPlanFrame(robot_pose);
130  auto [transformed_plan, lower_bound] = getGlobalPlanConsideringBoundsInCostmapFrame(global_pose);
131 
132  prunePlan(global_plan_up_to_inversion_, lower_bound);
133 
134  if (enforce_path_inversion_ && inversion_locale_ != 0u) {
135  if (isWithinInversionTolerances(global_pose)) {
136  prunePlan(global_plan_, global_plan_.poses.begin() + inversion_locale_);
137  global_plan_up_to_inversion_ = global_plan_;
138  inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
139  }
140  }
141 
142  if (transformed_plan.poses.empty()) {
143  throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
144  }
145 
146  return transformed_plan;
147 }
148 
150 {
151  const auto & costmap = costmap_->getCostmap();
152  return static_cast<double>(std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY())) *
153  costmap->getResolution() * 0.50;
154 }
155 
156 void PathHandler::setPath(const nav_msgs::msg::Path & plan)
157 {
158  global_plan_ = plan;
159  global_plan_up_to_inversion_ = global_plan_;
160  if (enforce_path_inversion_) {
161  inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
162  }
163 }
164 
165 nav_msgs::msg::Path & PathHandler::getPath() {return global_plan_;}
166 
167 void PathHandler::prunePlan(nav_msgs::msg::Path & plan, const PathIterator end)
168 {
169  plan.poses.erase(plan.poses.begin(), end);
170 }
171 
172 geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal(
173  const builtin_interfaces::msg::Time & stamp)
174 {
175  auto goal = global_plan_.poses.back();
176  goal.header.frame_id = global_plan_.header.frame_id;
177  goal.header.stamp = stamp;
178  if (goal.header.frame_id.empty()) {
179  throw nav2_core::ControllerTFError("Goal pose has an empty frame_id");
180  }
181  geometry_msgs::msg::PoseStamped transformed_goal;
182  if (!nav2_util::transformPoseInTargetFrame(goal, transformed_goal, *tf_buffer_,
183  costmap_->getGlobalFrameID(), transform_tolerance_))
184  {
185  throw nav2_core::ControllerTFError("Unable to transform goal pose into costmap frame");
186  }
187  return transformed_goal;
188 }
189 
190 bool PathHandler::isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose)
191 {
192  // Keep full path if we are within tolerance of the inversion pose
193  const auto last_pose = global_plan_up_to_inversion_.poses.back();
194  float distance = hypotf(
195  robot_pose.pose.position.x - last_pose.pose.position.x,
196  robot_pose.pose.position.y - last_pose.pose.position.y);
197 
198  float angle_distance = angles::shortest_angular_distance(
199  tf2::getYaw(robot_pose.pose.orientation),
200  tf2::getYaw(last_pose.pose.orientation));
201 
202  return distance <= inversion_xy_tolerance_ && fabs(angle_distance) <= inversion_yaw_tolerance;
203 }
204 
205 } // namespace mppi
Handles getting parameters and dynamic parameter changes.
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped &robot_pose)
Check if the robot pose is within the set inversion tolerances.
std::pair< nav_msgs::msg::Path, PathIterator > getGlobalPlanConsideringBoundsInCostmapFrame(const geometry_msgs::msg::PoseStamped &global_pose)
Get global plan within window of the local costmap size.
nav_msgs::msg::Path & getPath()
Get reference path.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
double getMaxCostmapDist()
Get largest dimension of costmap (radially)
void initialize(nav2::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, std::shared_ptr< tf2_ros::Buffer >, ParametersHandler *)
Initialize path handler on bringup.
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
void prunePlan(nav_msgs::msg::Path &plan, const PathIterator end)
Prune a path to only interesting portions.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
geometry_msgs::msg::PoseStamped transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped &pose)
Transform a pose to the global reference frame.