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