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