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