Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
node_hybrid.cpp
1 // Copyright (c) 2020, Samsung Research America
2 // Copyright (c) 2020, Applied Electric Vehicles Pty Ltd
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #include <math.h>
17 #include <chrono>
18 #include <vector>
19 #include <memory>
20 #include <algorithm>
21 #include <queue>
22 #include <limits>
23 #include <utility>
24 
25 #include "ompl/base/ScopedState.h"
26 #include "ompl/base/spaces/DubinsStateSpace.h"
27 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
28 
29 #include "nav2_smac_planner/node_hybrid.hpp"
30 
31 using namespace std::chrono; // NOLINT
32 
33 namespace nav2_smac_planner
34 {
35 
36 // defining static member for all instance to share
37 LookupTable NodeHybrid::obstacle_heuristic_lookup_table;
38 double NodeHybrid::travel_distance_cost = sqrt(2);
39 HybridMotionTable NodeHybrid::motion_table;
40 float NodeHybrid::size_lookup = 25;
41 LookupTable NodeHybrid::dist_heuristic_lookup_table;
42 nav2_costmap_2d::Costmap2D * NodeHybrid::sampled_costmap = nullptr;
43 CostmapDownsampler NodeHybrid::downsampler;
44 ObstacleHeuristicQueue NodeHybrid::obstacle_heuristic_queue;
45 
46 // Each of these tables are the projected motion models through
47 // time and space applied to the search on the current node in
48 // continuous map-coordinates (e.g. not meters but partial map cells)
49 // Currently, these are set to project *at minimum* into a neighboring
50 // cell. Though this could be later modified to project a certain
51 // amount of time or particular distance forward.
52 
53 // http://planning.cs.uiuc.edu/node821.html
54 // Model for ackermann style vehicle with minimum radius restriction
55 void HybridMotionTable::initDubin(
56  unsigned int & size_x_in,
57  unsigned int & /*size_y_in*/,
58  unsigned int & num_angle_quantization_in,
59  SearchInfo & search_info)
60 {
61  size_x = size_x_in;
62  change_penalty = search_info.change_penalty;
63  non_straight_penalty = search_info.non_straight_penalty;
64  cost_penalty = search_info.cost_penalty;
65  reverse_penalty = search_info.reverse_penalty;
66  travel_distance_reward = 1.0f - search_info.retrospective_penalty;
67 
68  // if nothing changed, no need to re-compute primitives
69  if (num_angle_quantization_in == num_angle_quantization &&
70  min_turning_radius == search_info.minimum_turning_radius &&
71  motion_model == MotionModel::DUBIN)
72  {
73  return;
74  }
75 
76  num_angle_quantization = num_angle_quantization_in;
77  num_angle_quantization_float = static_cast<float>(num_angle_quantization);
78  min_turning_radius = search_info.minimum_turning_radius;
79  motion_model = MotionModel::DUBIN;
80 
81  // angle must meet 3 requirements:
82  // 1) be increment of quantized bin size
83  // 2) chord length must be greater than sqrt(2) to leave current cell
84  // 3) maximum curvature must be respected, represented by minimum turning angle
85  // Thusly:
86  // On circle of radius minimum turning angle, we need select motion primatives
87  // with chord length > sqrt(2) and be an increment of our bin size
88  //
89  // chord >= sqrt(2) >= 2 * R * sin (angle / 2); where angle / N = quantized bin size
90  // Thusly: angle <= 2.0 * asin(sqrt(2) / (2 * R))
91  float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius));
92  // Now make sure angle is an increment of the quantized bin size
93  // And since its based on the minimum chord, we need to make sure its always larger
94  bin_size =
95  2.0f * static_cast<float>(M_PI) / static_cast<float>(num_angle_quantization);
96  float increments;
97  if (angle < bin_size) {
98  increments = 1.0f;
99  } else {
100  // Search dimensions are clean multiples of quantization - this prevents
101  // paths with loops in them
102  increments = ceil(angle / bin_size);
103  }
104  angle = increments * bin_size;
105 
106  // find deflections
107  // If we make a right triangle out of the chord in circle of radius
108  // min turning angle, we can see that delta X = R * sin (angle)
109  float delta_x = min_turning_radius * sin(angle);
110  // Using that same right triangle, we can see that the complement
111  // to delta Y is R * cos (angle). If we subtract R, we get the actual value
112  float delta_y = min_turning_radius - (min_turning_radius * cos(angle));
113 
114  projections.clear();
115  projections.reserve(3);
116  projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward
117  projections.emplace_back(delta_x, delta_y, increments); // Left
118  projections.emplace_back(delta_x, -delta_y, -increments); // Right
119 
120  // Create the correct OMPL state space
121  state_space = std::make_unique<ompl::base::DubinsStateSpace>(min_turning_radius);
122 
123  // Precompute projection deltas
124  delta_xs.resize(projections.size());
125  delta_ys.resize(projections.size());
126  trig_values.resize(num_angle_quantization);
127 
128  for (unsigned int i = 0; i != projections.size(); i++) {
129  delta_xs[i].resize(num_angle_quantization);
130  delta_ys[i].resize(num_angle_quantization);
131 
132  for (unsigned int j = 0; j != num_angle_quantization; j++) {
133  double cos_theta = cos(bin_size * j);
134  double sin_theta = sin(bin_size * j);
135  if (i == 0) {
136  // if first iteration, cache the trig values for later
137  trig_values[j] = {cos_theta, sin_theta};
138  }
139  delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta;
140  delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta;
141  }
142  }
143 }
144 
145 // http://planning.cs.uiuc.edu/node822.html
146 // Same as Dubin model but now reverse is valid
147 // See notes in Dubin for explanation
148 void HybridMotionTable::initReedsShepp(
149  unsigned int & size_x_in,
150  unsigned int & /*size_y_in*/,
151  unsigned int & num_angle_quantization_in,
152  SearchInfo & search_info)
153 {
154  size_x = size_x_in;
155  change_penalty = search_info.change_penalty;
156  non_straight_penalty = search_info.non_straight_penalty;
157  cost_penalty = search_info.cost_penalty;
158  reverse_penalty = search_info.reverse_penalty;
159  travel_distance_reward = 1.0f - search_info.retrospective_penalty;
160 
161  // if nothing changed, no need to re-compute primitives
162  if (num_angle_quantization_in == num_angle_quantization &&
163  min_turning_radius == search_info.minimum_turning_radius &&
164  motion_model == MotionModel::REEDS_SHEPP)
165  {
166  return;
167  }
168 
169  num_angle_quantization = num_angle_quantization_in;
170  num_angle_quantization_float = static_cast<float>(num_angle_quantization);
171  min_turning_radius = search_info.minimum_turning_radius;
172  motion_model = MotionModel::REEDS_SHEPP;
173 
174  float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius));
175  bin_size =
176  2.0f * static_cast<float>(M_PI) / static_cast<float>(num_angle_quantization);
177  float increments;
178  if (angle < bin_size) {
179  increments = 1.0f;
180  } else {
181  increments = ceil(angle / bin_size);
182  }
183  angle = increments * bin_size;
184 
185  float delta_x = min_turning_radius * sin(angle);
186  float delta_y = min_turning_radius - (min_turning_radius * cos(angle));
187 
188  projections.clear();
189  projections.reserve(6);
190  projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward
191  projections.emplace_back(delta_x, delta_y, increments); // Forward + Left
192  projections.emplace_back(delta_x, -delta_y, -increments); // Forward + Right
193  projections.emplace_back(-hypotf(delta_x, delta_y), 0.0, 0.0); // Backward
194  projections.emplace_back(-delta_x, delta_y, -increments); // Backward + Left
195  projections.emplace_back(-delta_x, -delta_y, increments); // Backward + Right
196 
197  // Create the correct OMPL state space
198  state_space = std::make_unique<ompl::base::ReedsSheppStateSpace>(min_turning_radius);
199 
200  // Precompute projection deltas
201  delta_xs.resize(projections.size());
202  delta_ys.resize(projections.size());
203  trig_values.resize(num_angle_quantization);
204 
205  for (unsigned int i = 0; i != projections.size(); i++) {
206  delta_xs[i].resize(num_angle_quantization);
207  delta_ys[i].resize(num_angle_quantization);
208 
209  for (unsigned int j = 0; j != num_angle_quantization; j++) {
210  double cos_theta = cos(bin_size * j);
211  double sin_theta = sin(bin_size * j);
212  if (i == 0) {
213  // if first iteration, cache the trig values for later
214  trig_values[j] = {cos_theta, sin_theta};
215  }
216  delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta;
217  delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta;
218  }
219  }
220 }
221 
222 MotionPoses HybridMotionTable::getProjections(const NodeHybrid * node)
223 {
224  MotionPoses projection_list;
225  projection_list.reserve(projections.size());
226 
227  for (unsigned int i = 0; i != projections.size(); i++) {
228  const MotionPose & motion_model = projections[i];
229 
230  // normalize theta, I know its overkill, but I've been burned before...
231  const float & node_heading = node->pose.theta;
232  float new_heading = node_heading + motion_model._theta;
233 
234  if (new_heading < 0.0) {
235  new_heading += num_angle_quantization_float;
236  }
237 
238  if (new_heading >= num_angle_quantization_float) {
239  new_heading -= num_angle_quantization_float;
240  }
241 
242  projection_list.emplace_back(
243  delta_xs[i][node_heading] + node->pose.x,
244  delta_ys[i][node_heading] + node->pose.y,
245  new_heading);
246  }
247 
248  return projection_list;
249 }
250 
251 unsigned int HybridMotionTable::getClosestAngularBin(const double & theta)
252 {
253  auto bin = static_cast<unsigned int>(round(static_cast<float>(theta) / bin_size));
254  return bin < num_angle_quantization ? bin : 0u;
255 }
256 
257 float HybridMotionTable::getAngleFromBin(const unsigned int & bin_idx)
258 {
259  return bin_idx * bin_size;
260 }
261 
262 NodeHybrid::NodeHybrid(const unsigned int index)
263 : parent(nullptr),
264  pose(0.0f, 0.0f, 0.0f),
265  _cell_cost(std::numeric_limits<float>::quiet_NaN()),
266  _accumulated_cost(std::numeric_limits<float>::max()),
267  _index(index),
268  _was_visited(false),
269  _motion_primitive_index(std::numeric_limits<unsigned int>::max())
270 {
271 }
272 
274 {
275  parent = nullptr;
276 }
277 
279 {
280  parent = nullptr;
281  _cell_cost = std::numeric_limits<float>::quiet_NaN();
282  _accumulated_cost = std::numeric_limits<float>::max();
283  _was_visited = false;
284  _motion_primitive_index = std::numeric_limits<unsigned int>::max();
285  pose.x = 0.0f;
286  pose.y = 0.0f;
287  pose.theta = 0.0f;
288 }
289 
291  const bool & traverse_unknown,
292  GridCollisionChecker * collision_checker)
293 {
294  if (collision_checker->inCollision(
295  this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown))
296  {
297  return false;
298  }
299 
300  _cell_cost = collision_checker->getCost();
301  return true;
302 }
303 
305 {
306  const float normalized_cost = child->getCost() / 252.0;
307  if (std::isnan(normalized_cost)) {
308  throw std::runtime_error(
309  "Node attempted to get traversal "
310  "cost without a known SE2 collision cost!");
311  }
312 
313  // this is the first node
314  if (getMotionPrimitiveIndex() == std::numeric_limits<unsigned int>::max()) {
315  return NodeHybrid::travel_distance_cost;
316  }
317 
318  float travel_cost = 0.0;
319  float travel_cost_raw =
320  NodeHybrid::travel_distance_cost *
321  (motion_table.travel_distance_reward + motion_table.cost_penalty * normalized_cost);
322 
323  if (child->getMotionPrimitiveIndex() == 0 || child->getMotionPrimitiveIndex() == 3) {
324  // New motion is a straight motion, no additional costs to be applied
325  travel_cost = travel_cost_raw;
326  } else {
328  // Turning motion but keeps in same direction: encourages to commit to turning if starting it
329  travel_cost = travel_cost_raw * motion_table.non_straight_penalty;
330  } else {
331  // Turning motion and changing direction: penalizes wiggling
332  travel_cost = travel_cost_raw *
333  (motion_table.non_straight_penalty + motion_table.change_penalty);
334  }
335  }
336 
337  if (child->getMotionPrimitiveIndex() > 2) {
338  // reverse direction
339  travel_cost *= motion_table.reverse_penalty;
340  }
341 
342  return travel_cost;
343 }
344 
346  const Coordinates & node_coords,
347  const Coordinates & goal_coords,
348  const nav2_costmap_2d::Costmap2D * /*costmap*/)
349 {
350  const float obstacle_heuristic =
351  getObstacleHeuristic(node_coords, goal_coords, motion_table.cost_penalty);
352  const float dist_heuristic = getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic);
353  return std::max(obstacle_heuristic, dist_heuristic);
354 }
355 
357  const MotionModel & motion_model,
358  unsigned int & size_x,
359  unsigned int & size_y,
360  unsigned int & num_angle_quantization,
361  SearchInfo & search_info)
362 {
363  // find the motion model selected
364  switch (motion_model) {
365  case MotionModel::DUBIN:
366  motion_table.initDubin(size_x, size_y, num_angle_quantization, search_info);
367  break;
368  case MotionModel::REEDS_SHEPP:
369  motion_table.initReedsShepp(size_x, size_y, num_angle_quantization, search_info);
370  break;
371  default:
372  throw std::runtime_error(
373  "Invalid motion model for Hybrid A*. Please select between"
374  " Dubin (Ackermann forward only),"
375  " Reeds-Shepp (Ackermann forward and back).");
376  }
377 
378  travel_distance_cost = motion_table.projections[0]._x;
379 }
380 
381 inline float distanceHeuristic2D(
382  const unsigned int idx, const unsigned int size_x,
383  const unsigned int target_x, const unsigned int target_y)
384 {
385  int dx = static_cast<int>(idx % size_x) - static_cast<int>(target_x);
386  int dy = static_cast<int>(idx / size_x) - static_cast<int>(target_y);
387  return std::sqrt(dx * dx + dy * dy);
388 }
389 
391  nav2_costmap_2d::Costmap2D * costmap,
392  const unsigned int & start_x, const unsigned int & start_y,
393  const unsigned int & goal_x, const unsigned int & goal_y)
394 {
395  // Downsample costmap 2x to compute a sparse obstacle heuristic. This speeds up
396  // the planner considerably to search through 75% less cells with no detectable
397  // erosion of path quality after even modest smoothing. The error would be no more
398  // than 0.05 * normalized cost. Since this is just a search prior, there's no loss in generality
399  std::weak_ptr<nav2_util::LifecycleNode> ptr;
400  downsampler.on_configure(ptr, "fake_frame", "fake_topic", costmap, 2.0, true);
401  downsampler.on_activate();
402  sampled_costmap = downsampler.downsample(2.0);
403 
404  // Clear lookup table
405  unsigned int size = sampled_costmap->getSizeInCellsX() * sampled_costmap->getSizeInCellsY();
406  if (obstacle_heuristic_lookup_table.size() == size) {
407  // must reset all values
408  std::fill(
409  obstacle_heuristic_lookup_table.begin(),
410  obstacle_heuristic_lookup_table.end(), 0.0);
411  } else {
412  unsigned int obstacle_size = obstacle_heuristic_lookup_table.size();
413  obstacle_heuristic_lookup_table.resize(size, 0.0);
414  // must reset values for non-constructed indices
415  std::fill_n(
416  obstacle_heuristic_lookup_table.begin(), obstacle_size, 0.0);
417  }
418 
419  obstacle_heuristic_queue.clear();
420  obstacle_heuristic_queue.reserve(
421  sampled_costmap->getSizeInCellsX() * sampled_costmap->getSizeInCellsY());
422 
423  // Set initial goal point to queue from. Divided by 2 due to downsampled costmap.
424  const unsigned int size_x = sampled_costmap->getSizeInCellsX();
425  const unsigned int goal_index = floor(goal_y / 2.0) * size_x + floor(goal_x / 2.0);
426  obstacle_heuristic_queue.emplace_back(
427  distanceHeuristic2D(goal_index, size_x, start_x, start_y), goal_index);
428 
429  // initialize goal cell with a very small value to differentiate it from 0.0 (~uninitialized)
430  // the negative value means the cell is in the open set
431  obstacle_heuristic_lookup_table[goal_index] = -0.00001f;
432 }
433 
435  const Coordinates & node_coords,
436  const Coordinates & goal_coords,
437  const double & cost_penalty)
438 {
439  // If already expanded, return the cost
440  const unsigned int size_x = sampled_costmap->getSizeInCellsX();
441  // Divided by 2 due to downsampled costmap.
442  const unsigned int start_y = floor(node_coords.y / 2.0);
443  const unsigned int start_x = floor(node_coords.x / 2.0);
444  const unsigned int start_index = start_y * size_x + start_x;
445  const float & requested_node_cost = obstacle_heuristic_lookup_table[start_index];
446  if (requested_node_cost > 0.0f) {
447  // costs are doubled due to downsampling
448  return 2.0 * requested_node_cost;
449  }
450 
451  // If not, expand until it is included. This dynamic programming ensures that
452  // we only expand the MINIMUM spanning set of the costmap per planning request.
453  // Rather than naively expanding the entire (potentially massive) map for a limited
454  // path, we only expand to the extent required for the furthest expansion in the
455  // search-planning request that dynamically updates during search as needed.
456 
457  // start_x and start_y have changed since last call
458  // we need to recompute 2D distance heuristic and reprioritize queue
459  for (auto & n : obstacle_heuristic_queue) {
460  n.first = -obstacle_heuristic_lookup_table[n.second] +
461  distanceHeuristic2D(n.second, size_x, start_x, start_y);
462  }
463  std::make_heap(
464  obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
466 
467  const int size_x_int = static_cast<int>(size_x);
468  const unsigned int size_y = sampled_costmap->getSizeInCellsY();
469  const float sqrt_2 = sqrt(2);
470  float c_cost, cost, travel_cost, new_cost, existing_cost;
471  unsigned int idx, mx, my, mx_idx, my_idx;
472  unsigned int new_idx = 0;
473 
474  const std::vector<int> neighborhood = {1, -1, // left right
475  size_x_int, -size_x_int, // up down
476  size_x_int + 1, size_x_int - 1, // upper diagonals
477  -size_x_int + 1, -size_x_int - 1}; // lower diagonals
478 
479  while (!obstacle_heuristic_queue.empty()) {
480  idx = obstacle_heuristic_queue.front().second;
481  std::pop_heap(
482  obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
484  obstacle_heuristic_queue.pop_back();
485  c_cost = obstacle_heuristic_lookup_table[idx];
486  if (c_cost > 0.0f) {
487  // cell has been processed and closed, no further cost improvements
488  // are mathematically possible thanks to euclidean distance heuristic consistency
489  continue;
490  }
491  c_cost = -c_cost;
492  obstacle_heuristic_lookup_table[idx] = c_cost; // set a positive value to close the cell
493 
494  my_idx = idx / size_x;
495  mx_idx = idx - (my_idx * size_x);
496 
497  // find neighbors
498  for (unsigned int i = 0; i != neighborhood.size(); i++) {
499  new_idx = static_cast<unsigned int>(static_cast<int>(idx) + neighborhood[i]);
500 
501  // if neighbor path is better and non-lethal, set new cost and add to queue
502  if (new_idx < size_x * size_y) {
503  cost = static_cast<float>(sampled_costmap->getCost(new_idx));
504  if (cost >= INSCRIBED) {
505  continue;
506  }
507 
508  my = new_idx / size_x;
509  mx = new_idx - (my * size_x);
510 
511  if (mx == 0 && mx_idx >= size_x - 1 || mx >= size_x - 1 && mx_idx == 0) {
512  continue;
513  }
514  if (my == 0 && my_idx >= size_y - 1 || my >= size_y - 1 && my_idx == 0) {
515  continue;
516  }
517 
518  existing_cost = obstacle_heuristic_lookup_table[new_idx];
519  if (existing_cost <= 0.0f) {
520  travel_cost =
521  ((i <= 3) ? 1.0f : sqrt_2) * (1.0f + (cost_penalty * cost / 252.0f));
522  new_cost = c_cost + travel_cost;
523  if (existing_cost == 0.0f || -existing_cost > new_cost) {
524  // the negative value means the cell is in the open set
525  obstacle_heuristic_lookup_table[new_idx] = -new_cost;
526  obstacle_heuristic_queue.emplace_back(
527  new_cost + distanceHeuristic2D(new_idx, size_x, start_x, start_y), new_idx);
528  std::push_heap(
529  obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
531  }
532  }
533  }
534  }
535 
536  if (idx == start_index) {
537  break;
538  }
539  }
540 
541  // return requested_node_cost which has been updated by the search
542  // costs are doubled due to downsampling
543  return 2.0 * requested_node_cost;
544 }
545 
547  const Coordinates & node_coords,
548  const Coordinates & goal_coords,
549  const float & obstacle_heuristic)
550 {
551  // rotate and translate node_coords such that goal_coords relative is (0,0,0)
552  // Due to the rounding involved in exact cell increments for caching,
553  // this is not an exact replica of a live heuristic, but has bounded error.
554  // (Usually less than 1 cell)
555 
556  // This angle is negative since we are de-rotating the current node
557  // by the goal angle; cos(-th) = cos(th) & sin(-th) = -sin(th)
558  const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
559  const float cos_th = trig_vals.first;
560  const float sin_th = -trig_vals.second;
561  const float dx = node_coords.x - goal_coords.x;
562  const float dy = node_coords.y - goal_coords.y;
563 
564  double dtheta_bin = node_coords.theta - goal_coords.theta;
565  if (dtheta_bin < 0) {
566  dtheta_bin += motion_table.num_angle_quantization;
567  }
568  if (dtheta_bin > motion_table.num_angle_quantization) {
569  dtheta_bin -= motion_table.num_angle_quantization;
570  }
571 
572  Coordinates node_coords_relative(
573  round(dx * cos_th - dy * sin_th),
574  round(dx * sin_th + dy * cos_th),
575  round(dtheta_bin));
576 
577  // Check if the relative node coordinate is within the localized window around the goal
578  // to apply the distance heuristic. Since the lookup table is contains only the positive
579  // X axis, we mirror the Y and theta values across the X axis to find the heuristic values.
580  float motion_heuristic = 0.0;
581  const int floored_size = floor(size_lookup / 2.0);
582  const int ceiling_size = ceil(size_lookup / 2.0);
583  const float mirrored_relative_y = abs(node_coords_relative.y);
584  if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
585  // Need to mirror angle if Y coordinate was mirrored
586  int theta_pos;
587  if (node_coords_relative.y < 0.0) {
588  theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
589  } else {
590  theta_pos = node_coords_relative.theta;
591  }
592  const int x_pos = node_coords_relative.x + floored_size;
593  const int y_pos = static_cast<int>(mirrored_relative_y);
594  const int index =
595  x_pos * ceiling_size * motion_table.num_angle_quantization +
596  y_pos * motion_table.num_angle_quantization +
597  theta_pos;
598  motion_heuristic = dist_heuristic_lookup_table[index];
599  } else if (obstacle_heuristic <= 0.0) {
600  // If no obstacle heuristic value, must have some H to use
601  // In nominal situations, this should never be called.
602  static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
603  to[0] = goal_coords.x;
604  to[1] = goal_coords.y;
605  to[2] = goal_coords.theta * motion_table.num_angle_quantization;
606  from[0] = node_coords.x;
607  from[1] = node_coords.y;
608  from[2] = node_coords.theta * motion_table.num_angle_quantization;
609  motion_heuristic = motion_table.state_space->distance(from(), to());
610  }
611 
612  return motion_heuristic;
613 }
614 
616  const float & lookup_table_dim,
617  const MotionModel & motion_model,
618  const unsigned int & dim_3_size,
619  const SearchInfo & search_info)
620 {
621  // Dubin or Reeds-Shepp shortest distances
622  if (motion_model == MotionModel::DUBIN) {
623  motion_table.state_space = std::make_unique<ompl::base::DubinsStateSpace>(
624  search_info.minimum_turning_radius);
625  } else if (motion_model == MotionModel::REEDS_SHEPP) {
626  motion_table.state_space = std::make_unique<ompl::base::ReedsSheppStateSpace>(
627  search_info.minimum_turning_radius);
628  } else {
629  throw std::runtime_error(
630  "Node attempted to precompute distance heuristics "
631  "with invalid motion model!");
632  }
633 
634  ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
635  to[0] = 0.0;
636  to[1] = 0.0;
637  to[2] = 0.0;
638  size_lookup = lookup_table_dim;
639  float motion_heuristic = 0.0;
640  unsigned int index = 0;
641  int dim_3_size_int = static_cast<int>(dim_3_size);
642  float angular_bin_size = 2 * M_PI / static_cast<float>(dim_3_size);
643 
644  // Create a lookup table of Dubin/Reeds-Shepp distances in a window around the goal
645  // to help drive the search towards admissible approaches. Deu to symmetries in the
646  // Heuristic space, we need to only store 2 of the 4 quadrants and simply mirror
647  // around the X axis any relative node lookup. This reduces memory overhead and increases
648  // the size of a window a platform can store in memory.
649  dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
650  for (float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
651  for (float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
652  for (int heading = 0; heading != dim_3_size_int; heading++) {
653  from[0] = x;
654  from[1] = y;
655  from[2] = heading * angular_bin_size;
656  motion_heuristic = motion_table.state_space->distance(from(), to());
657  dist_heuristic_lookup_table[index] = motion_heuristic;
658  index++;
659  }
660  }
661  }
662 }
663 
665  std::function<bool(const unsigned int &, nav2_smac_planner::NodeHybrid * &)> & NeighborGetter,
666  GridCollisionChecker * collision_checker,
667  const bool & traverse_unknown,
668  NodeVector & neighbors)
669 {
670  unsigned int index = 0;
671  NodePtr neighbor = nullptr;
672  Coordinates initial_node_coords;
673  const MotionPoses motion_projections = motion_table.getProjections(this);
674 
675  for (unsigned int i = 0; i != motion_projections.size(); i++) {
676  index = NodeHybrid::getIndex(
677  static_cast<unsigned int>(motion_projections[i]._x),
678  static_cast<unsigned int>(motion_projections[i]._y),
679  static_cast<unsigned int>(motion_projections[i]._theta),
680  motion_table.size_x, motion_table.num_angle_quantization);
681 
682  if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) {
683  // Cache the initial pose in case it was visited but valid
684  // don't want to disrupt continuous coordinate expansion
685  initial_node_coords = neighbor->pose;
686  neighbor->setPose(
687  Coordinates(
688  motion_projections[i]._x,
689  motion_projections[i]._y,
690  motion_projections[i]._theta));
691  if (neighbor->isNodeValid(traverse_unknown, collision_checker)) {
692  neighbor->setMotionPrimitiveIndex(i);
693  neighbors.push_back(neighbor);
694  } else {
695  neighbor->setPose(initial_node_coords);
696  }
697  }
698  }
699 }
700 
701 bool NodeHybrid::backtracePath(CoordinateVector & path)
702 {
703  if (!this->parent) {
704  return false;
705  }
706 
707  NodePtr current_node = this;
708 
709  while (current_node->parent) {
710  path.push_back(current_node->pose);
711  // Convert angle to radians
712  path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta);
713  current_node = current_node->parent;
714  }
715 
716  // add the start pose
717  path.push_back(current_node->pose);
718  // Convert angle to radians
719  path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta);
720 
721  return true;
722 }
723 
724 } // 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
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
void on_activate()
Activate the publisher of the downsampled costmap.
void on_configure(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &global_frame, const std::string &topic_name, nav2_costmap_2d::Costmap2D *const costmap, const unsigned int &downsampling_factor, const bool &use_min_cost_neighbor=false)
Configure the downsampled costmap object and the ROS publisher.
nav2_costmap_2d::Costmap2D * downsample(const unsigned int &downsampling_factor)
Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.
A costmap grid collision checker.
bool inCollision(const float &x, const float &y, const float &theta, const bool &traverse_unknown)
Check if in collision with costmap and footprint at pose.
float getCost()
Get cost at footprint pose in costmap.
NodeHybrid implementation for graph, Hybrid-A*.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates, const nav2_costmap_2d::Costmap2D *costmap)
Get cost of heuristic of node.
static void precomputeDistanceHeuristic(const float &lookup_table_dim, const MotionModel &motion_model, const unsigned int &dim_3_size, const SearchInfo &search_info)
Compute the SE2 distance heuristic.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker)
Check if this node is valid.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
static void resetObstacleHeuristic(nav2_costmap_2d::Costmap2D *costmap, const unsigned int &start_x, const unsigned int &start_y, const unsigned int &goal_x, const unsigned int &goal_y)
reset the obstacle heuristic state
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
~NodeHybrid()
A destructor for nav2_smac_planner::NodeHybrid.
void setMotionPrimitiveIndex(const unsigned int &idx)
Sets the motion primitive index used to achieve node in search.
static void initMotionModel(const MotionModel &motion_model, unsigned int &size_x, unsigned int &size_y, unsigned int &angle_quantization, SearchInfo &search_info)
Initialize motion models.
void reset()
Reset method for new search.
unsigned int & getMotionPrimitiveIndex()
Gets the motion primitive index used to achieve node in search.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
bool & wasVisited()
Gets if cell has been visited in search.
void getNeighbors(std::function< bool(const unsigned int &, nav2_smac_planner::NodeHybrid *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
unsigned int & getIndex()
Gets cell index.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
float & getCost()
Gets the costmap cost at this node.
void initReedsShepp(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Reeds-Shepp model.
MotionPoses getProjections(const NodeHybrid *node)
Get projections of motion models.
void initDubin(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Dubin model.
Definition: node_hybrid.cpp:55
A struct for poses in motion primitives.
Definition: types.hpp:105
NodeHybrid implementation of coordinate structure.
Search properties and penalties.
Definition: types.hpp:36