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