Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
smoother.cpp
1 // Copyright (c) 2021, 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. Reserved.
14 
15 #include <ompl/base/ScopedState.h>
16 #include <ompl/base/spaces/DubinsStateSpace.h>
17 #include <vector>
18 #include <memory>
19 #include "nav2_smac_planner/smoother.hpp"
20 
21 namespace nav2_smac_planner
22 {
23 using namespace nav2_util::geometry_utils; // NOLINT
24 using namespace std::chrono; // NOLINT
25 
27 {
28  tolerance_ = params.tolerance_;
29  max_its_ = params.max_its_;
30  data_w_ = params.w_data_;
31  smooth_w_ = params.w_smooth_;
32  is_holonomic_ = params.holonomic_;
33  do_refinement_ = params.do_refinement_;
34  refinement_num_ = params.refinement_num_;
35 }
36 
37 void Smoother::initialize(const double & min_turning_radius)
38 {
39  min_turning_rad_ = min_turning_radius;
40  state_space_ = std::make_unique<ompl::base::DubinsStateSpace>(min_turning_rad_);
41 }
42 
44  nav_msgs::msg::Path & path,
45  const nav2_costmap_2d::Costmap2D * costmap,
46  const double & max_time)
47 {
48  // by-pass path orientations approximation when skipping smac smoother
49  if (max_its_ == 0) {
50  return false;
51  }
52 
53  steady_clock::time_point start = steady_clock::now();
54  double time_remaining = max_time;
55  bool success = true, reversing_segment;
56  nav_msgs::msg::Path curr_path_segment;
57  curr_path_segment.header = path.header;
58  std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
59 
60  for (unsigned int i = 0; i != path_segments.size(); i++) {
61  if (path_segments[i].end - path_segments[i].start > 10) {
62  // Populate path segment
63  curr_path_segment.poses.clear();
64  std::copy(
65  path.poses.begin() + path_segments[i].start,
66  path.poses.begin() + path_segments[i].end + 1,
67  std::back_inserter(curr_path_segment.poses));
68 
69  // Make sure we're still able to smooth with time remaining
70  steady_clock::time_point now = steady_clock::now();
71  time_remaining = max_time - duration_cast<duration<double>>(now - start).count();
72  refinement_ctr_ = 0;
73 
74  // Smooth path segment naively
75  const geometry_msgs::msg::Pose start_pose = curr_path_segment.poses.front().pose;
76  const geometry_msgs::msg::Pose goal_pose = curr_path_segment.poses.back().pose;
77  bool local_success =
78  smoothImpl(curr_path_segment, reversing_segment, costmap, time_remaining);
79  success = success && local_success;
80 
81  // Enforce boundary conditions
82  if (!is_holonomic_ && local_success) {
83  enforceStartBoundaryConditions(start_pose, curr_path_segment, costmap, reversing_segment);
84  enforceEndBoundaryConditions(goal_pose, curr_path_segment, costmap, reversing_segment);
85  }
86 
87  // Assemble the path changes to the main path
88  std::copy(
89  curr_path_segment.poses.begin(),
90  curr_path_segment.poses.end(),
91  path.poses.begin() + path_segments[i].start);
92  }
93  }
94 
95  return success;
96 }
97 
99  nav_msgs::msg::Path & path,
100  bool & reversing_segment,
101  const nav2_costmap_2d::Costmap2D * costmap,
102  const double & max_time)
103 {
104  steady_clock::time_point a = steady_clock::now();
105  rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
106 
107  int its = 0;
108  double change = tolerance_;
109  const unsigned int & path_size = path.poses.size();
110  double x_i, y_i, y_m1, y_ip1, y_i_org;
111  unsigned int mx, my;
112 
113  nav_msgs::msg::Path new_path = path;
114  nav_msgs::msg::Path last_path = path;
115 
116  while (change >= tolerance_) {
117  its += 1;
118  change = 0.0;
119 
120  // Make sure the smoothing function will converge
121  if (its >= max_its_) {
122  RCLCPP_DEBUG(
123  rclcpp::get_logger("SmacPlannerSmoother"),
124  "Number of iterations has exceeded limit of %i.", max_its_);
125  path = last_path;
126  updateApproximatePathOrientations(path, reversing_segment);
127  return false;
128  }
129 
130  // Make sure still have time left to process
131  steady_clock::time_point b = steady_clock::now();
132  rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
133  if (timespan > max_dur) {
134  RCLCPP_DEBUG(
135  rclcpp::get_logger("SmacPlannerSmoother"),
136  "Smoothing time exceeded allowed duration of %0.2f.", max_time);
137  path = last_path;
138  updateApproximatePathOrientations(path, reversing_segment);
139  return false;
140  }
141 
142  for (unsigned int i = 1; i != path_size - 1; i++) {
143  for (unsigned int j = 0; j != 2; j++) {
144  x_i = getFieldByDim(path.poses[i], j);
145  y_i = getFieldByDim(new_path.poses[i], j);
146  y_m1 = getFieldByDim(new_path.poses[i - 1], j);
147  y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
148  y_i_org = y_i;
149 
150  // Smooth based on local 3 point neighborhood and original data locations
151  y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
152  setFieldByDim(new_path.poses[i], j, y_i);
153  change += abs(y_i - y_i_org);
154  }
155 
156  // validate update is admissible, only checks cost if a valid costmap pointer is provided
157  float cost = 0.0;
158  if (costmap) {
159  costmap->worldToMap(
160  getFieldByDim(new_path.poses[i], 0),
161  getFieldByDim(new_path.poses[i], 1),
162  mx, my);
163  cost = static_cast<float>(costmap->getCost(mx, my));
164  }
165 
166  if (cost > MAX_NON_OBSTACLE && cost != UNKNOWN) {
167  RCLCPP_DEBUG(
168  rclcpp::get_logger("SmacPlannerSmoother"),
169  "Smoothing process resulted in an infeasible collision. "
170  "Returning the last path before the infeasibility was introduced.");
171  path = last_path;
172  updateApproximatePathOrientations(path, reversing_segment);
173  return false;
174  }
175  }
176 
177  last_path = new_path;
178  }
179 
180  // Lets do additional refinement, it shouldn't take more than a couple milliseconds
181  // but really puts the path quality over the top.
182  if (do_refinement_ && refinement_ctr_ < refinement_num_) {
183  refinement_ctr_++;
184  smoothImpl(new_path, reversing_segment, costmap, max_time);
185  }
186 
187  updateApproximatePathOrientations(new_path, reversing_segment);
188  path = new_path;
189  return true;
190 }
191 
193  const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim)
194 {
195  if (dim == 0) {
196  return msg.pose.position.x;
197  } else if (dim == 1) {
198  return msg.pose.position.y;
199  } else {
200  return msg.pose.position.z;
201  }
202 }
203 
205  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
206  const double & value)
207 {
208  if (dim == 0) {
209  msg.pose.position.x = value;
210  } else if (dim == 1) {
211  msg.pose.position.y = value;
212  } else {
213  msg.pose.position.z = value;
214  }
215 }
216 
217 std::vector<PathSegment> Smoother::findDirectionalPathSegments(const nav_msgs::msg::Path & path)
218 {
219  std::vector<PathSegment> segments;
220  PathSegment curr_segment;
221  curr_segment.start = 0;
222 
223  // If holonomic, no directional changes and
224  // may have abrupt angular changes from naive grid search
225  if (is_holonomic_) {
226  curr_segment.end = path.poses.size() - 1;
227  segments.push_back(curr_segment);
228  return segments;
229  }
230 
231  // Iterating through the path to determine the position of the cusp
232  for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
233  // We have two vectors for the dot product OA and AB. Determining the vectors.
234  double oa_x = path.poses[idx].pose.position.x -
235  path.poses[idx - 1].pose.position.x;
236  double oa_y = path.poses[idx].pose.position.y -
237  path.poses[idx - 1].pose.position.y;
238  double ab_x = path.poses[idx + 1].pose.position.x -
239  path.poses[idx].pose.position.x;
240  double ab_y = path.poses[idx + 1].pose.position.y -
241  path.poses[idx].pose.position.y;
242 
243  // Checking for the existance of cusp, in the path, using the dot product.
244  double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
245  if (dot_product < 0.0) {
246  curr_segment.end = idx;
247  segments.push_back(curr_segment);
248  curr_segment.start = idx;
249  }
250 
251  // Checking for the existance of a differential rotation in place.
252  double cur_theta = tf2::getYaw(path.poses[idx].pose.orientation);
253  double next_theta = tf2::getYaw(path.poses[idx + 1].pose.orientation);
254  double dtheta = angles::shortest_angular_distance(cur_theta, next_theta);
255  if (fabs(ab_x) < 1e-4 && fabs(ab_y) < 1e-4 && fabs(dtheta) > 1e-4) {
256  curr_segment.end = idx;
257  segments.push_back(curr_segment);
258  curr_segment.start = idx;
259  }
260  }
261 
262  curr_segment.end = path.poses.size() - 1;
263  segments.push_back(curr_segment);
264  return segments;
265 }
266 
268  nav_msgs::msg::Path & path,
269  bool & reversing_segment)
270 {
271  double dx, dy, theta, pt_yaw;
272  reversing_segment = false;
273 
274  // Find if this path segment is in reverse
275  dx = path.poses[2].pose.position.x - path.poses[1].pose.position.x;
276  dy = path.poses[2].pose.position.y - path.poses[1].pose.position.y;
277  theta = atan2(dy, dx);
278  pt_yaw = tf2::getYaw(path.poses[1].pose.orientation);
279  if (!is_holonomic_ && fabs(angles::shortest_angular_distance(pt_yaw, theta)) > M_PI_2) {
280  reversing_segment = true;
281  }
282 
283  // Find the angle relative the path position vectors
284  for (unsigned int i = 0; i != path.poses.size() - 1; i++) {
285  dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x;
286  dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y;
287  theta = atan2(dy, dx);
288 
289  // If points are overlapping, pass
290  if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
291  continue;
292  }
293 
294  // Flip the angle if this path segment is in reverse
295  if (reversing_segment) {
296  theta += M_PI; // orientationAroundZAxis will normalize
297  }
298 
299  path.poses[i].pose.orientation = orientationAroundZAxis(theta);
300  }
301 }
302 
304  const BoundaryExpansions & boundary_expansions)
305 {
306  // Check which is valid with the minimum integrated length such that
307  // shorter end-points away that are infeasible to achieve without
308  // a loop-de-loop are punished
309  double min_length = 1e9;
310  int shortest_boundary_expansion_idx = 1e9;
311  for (unsigned int idx = 0; idx != boundary_expansions.size(); idx++) {
312  if (boundary_expansions[idx].expansion_path_length<min_length &&
313  !boundary_expansions[idx].in_collision &&
314  boundary_expansions[idx].path_end_idx>0.0 &&
315  boundary_expansions[idx].expansion_path_length > 0.0)
316  {
317  min_length = boundary_expansions[idx].expansion_path_length;
318  shortest_boundary_expansion_idx = idx;
319  }
320  }
321 
322  return shortest_boundary_expansion_idx;
323 }
324 
326  const geometry_msgs::msg::Pose & start,
327  const geometry_msgs::msg::Pose & end,
328  BoundaryExpansion & expansion,
329  const nav2_costmap_2d::Costmap2D * costmap)
330 {
331  static ompl::base::ScopedState<> from(state_space_), to(state_space_), s(state_space_);
332 
333  from[0] = start.position.x;
334  from[1] = start.position.y;
335  from[2] = tf2::getYaw(start.orientation);
336  to[0] = end.position.x;
337  to[1] = end.position.y;
338  to[2] = tf2::getYaw(end.orientation);
339 
340  double d = state_space_->distance(from(), to());
341  // If this path is too long compared to the original, then this is probably
342  // a loop-de-loop, treat as invalid as to not deviate too far from the original path.
343  // 2.0 selected from prinicipled choice of boundary test points
344  // r, 2 * r, r * PI, and 2 * PI * r. If there is a loop, it will be
345  // approximately 2 * PI * r, which is 2 * PI > r, PI > 2 * r, and 2 > r * PI.
346  // For all but the last backup test point, a loop would be approximately
347  // 2x greater than any of the selections.
348  if (d > 2.0 * expansion.original_path_length) {
349  return;
350  }
351 
352  std::vector<double> reals;
353  double theta(0.0), x(0.0), y(0.0);
354  double x_m = start.position.x;
355  double y_m = start.position.y;
356 
357  // Get intermediary poses
358  for (double i = 0; i <= expansion.path_end_idx; i++) {
359  state_space_->interpolate(from(), to(), i / expansion.path_end_idx, s());
360  reals = s.reals();
361  // Make sure in range [0, 2PI)
362  theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
363  theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
364  x = reals[0];
365  y = reals[1];
366 
367  // Check for collision
368  unsigned int mx, my;
369  costmap->worldToMap(x, y, mx, my);
370  if (static_cast<float>(costmap->getCost(mx, my)) >= INSCRIBED) {
371  expansion.in_collision = true;
372  }
373 
374  // Integrate path length
375  expansion.expansion_path_length += hypot(x - x_m, y - y_m);
376  x_m = x;
377  y_m = y;
378 
379  // Store point
380  expansion.pts.emplace_back(x, y, theta);
381  }
382 }
383 
384 template<typename IteratorT>
385 BoundaryExpansions Smoother::generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
386 {
387  std::vector<double> distances = {
388  min_turning_rad_, // Radius
389  2.0 * min_turning_rad_, // Diameter
390  M_PI * min_turning_rad_, // 50% Circumference
391  2.0 * M_PI * min_turning_rad_ // Circumference
392  };
393 
394  BoundaryExpansions boundary_expansions;
395  boundary_expansions.resize(distances.size());
396  double curr_dist = 0.0;
397  double x_last = start->pose.position.x;
398  double y_last = start->pose.position.y;
399  geometry_msgs::msg::Point pt;
400  unsigned int curr_dist_idx = 0;
401 
402  for (IteratorT iter = start; iter != end; iter++) {
403  pt = iter->pose.position;
404  curr_dist += hypot(pt.x - x_last, pt.y - y_last);
405  x_last = pt.x;
406  y_last = pt.y;
407 
408  if (curr_dist >= distances[curr_dist_idx]) {
409  boundary_expansions[curr_dist_idx].path_end_idx = iter - start;
410  boundary_expansions[curr_dist_idx].original_path_length = curr_dist;
411  curr_dist_idx++;
412  }
413 
414  if (curr_dist_idx == boundary_expansions.size()) {
415  break;
416  }
417  }
418 
419  return boundary_expansions;
420 }
421 
423  const geometry_msgs::msg::Pose & start_pose,
424  nav_msgs::msg::Path & path,
425  const nav2_costmap_2d::Costmap2D * costmap,
426  const bool & reversing_segment)
427 {
428  // Find range of points for testing
429  BoundaryExpansions boundary_expansions =
430  generateBoundaryExpansionPoints<PathIterator>(path.poses.begin(), path.poses.end());
431 
432  // Generate the motion model and metadata from start -> test points
433  for (unsigned int i = 0; i != boundary_expansions.size(); i++) {
434  BoundaryExpansion & expansion = boundary_expansions[i];
435  if (expansion.path_end_idx == 0.0) {
436  continue;
437  }
438 
439  if (!reversing_segment) {
440  findBoundaryExpansion(
441  start_pose, path.poses[expansion.path_end_idx].pose, expansion,
442  costmap);
443  } else {
444  findBoundaryExpansion(
445  path.poses[expansion.path_end_idx].pose, start_pose, expansion,
446  costmap);
447  }
448  }
449 
450  // Find the shortest kinematically feasible boundary expansion
451  unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
452  if (best_expansion_idx > boundary_expansions.size()) {
453  return;
454  }
455 
456  // Override values to match curve
457  BoundaryExpansion & best_expansion = boundary_expansions[best_expansion_idx];
458  if (reversing_segment) {
459  std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
460  }
461  for (unsigned int i = 0; i != best_expansion.pts.size(); i++) {
462  path.poses[i].pose.position.x = best_expansion.pts[i].x;
463  path.poses[i].pose.position.y = best_expansion.pts[i].y;
464  path.poses[i].pose.orientation = orientationAroundZAxis(best_expansion.pts[i].theta);
465  }
466 }
467 
469  const geometry_msgs::msg::Pose & end_pose,
470  nav_msgs::msg::Path & path,
471  const nav2_costmap_2d::Costmap2D * costmap,
472  const bool & reversing_segment)
473 {
474  // Find range of points for testing
475  BoundaryExpansions boundary_expansions =
476  generateBoundaryExpansionPoints<ReversePathIterator>(path.poses.rbegin(), path.poses.rend());
477 
478  // Generate the motion model and metadata from start -> test points
479  unsigned int expansion_starting_idx;
480  for (unsigned int i = 0; i != boundary_expansions.size(); i++) {
481  BoundaryExpansion & expansion = boundary_expansions[i];
482  if (expansion.path_end_idx == 0.0) {
483  continue;
484  }
485  expansion_starting_idx = path.poses.size() - expansion.path_end_idx - 1;
486  if (!reversing_segment) {
487  findBoundaryExpansion(path.poses[expansion_starting_idx].pose, end_pose, expansion, costmap);
488  } else {
489  findBoundaryExpansion(end_pose, path.poses[expansion_starting_idx].pose, expansion, costmap);
490  }
491  }
492 
493  // Find the shortest kinematically feasible boundary expansion
494  unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
495  if (best_expansion_idx > boundary_expansions.size()) {
496  return;
497  }
498 
499  // Override values to match curve
500  BoundaryExpansion & best_expansion = boundary_expansions[best_expansion_idx];
501  if (reversing_segment) {
502  std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
503  }
504  expansion_starting_idx = path.poses.size() - best_expansion.path_end_idx - 1;
505  for (unsigned int i = 0; i != best_expansion.pts.size(); i++) {
506  path.poses[expansion_starting_idx + i].pose.position.x = best_expansion.pts[i].x;
507  path.poses[expansion_starting_idx + i].pose.position.y = best_expansion.pts[i].y;
508  path.poses[expansion_starting_idx + i].pose.orientation = orientationAroundZAxis(
509  best_expansion.pts[i].theta);
510  }
511 }
512 
513 } // namespace nav2_smac_planner
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:285
void initialize(const double &min_turning_radius)
Initialization of the smoother.
Definition: smoother.cpp:37
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
Definition: smoother.cpp:43
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
Definition: smoother.cpp:98
void updateApproximatePathOrientations(nav_msgs::msg::Path &path, bool &reversing_segment)
For a given path, update the path point orientations based on smoothing.
Definition: smoother.cpp:267
std::vector< PathSegment > findDirectionalPathSegments(const nav_msgs::msg::Path &path)
Finds the starting and end indices of path segments where the robot is traveling in the same directio...
Definition: smoother.cpp:217
void enforceStartBoundaryConditions(const geometry_msgs::msg::Pose &start_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
Definition: smoother.cpp:422
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
Definition: smoother.cpp:192
void enforceEndBoundaryConditions(const geometry_msgs::msg::Pose &end_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
Definition: smoother.cpp:468
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
Definition: smoother.cpp:204
Smoother(const SmootherParams &params)
A constructor for nav2_smac_planner::Smoother.
Definition: smoother.cpp:26
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
Definition: smoother.cpp:385
unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions &boundary_expansions)
Given a set of boundary expansion, find the one which is shortest such that it is least likely to con...
Definition: smoother.cpp:303
void findBoundaryExpansion(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &end, BoundaryExpansion &expansion, const nav2_costmap_2d::Costmap2D *costmap)
Populate a motion model expansion from start->end into expansion.
Definition: smoother.cpp:325
Boundary expansion state.
Definition: smoother.hpp:71
A segment of a path in start/end indices.
Definition: smoother.hpp:43
Parameters for the smoother cost function.