Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
node_lattice.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 <math.h>
16 #include <chrono>
17 #include <vector>
18 #include <memory>
19 #include <algorithm>
20 #include <queue>
21 #include <limits>
22 #include <string>
23 #include <fstream>
24 #include <cmath>
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_lattice.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 LatticeMotionTable NodeLattice::motion_table;
39 float NodeLattice::size_lookup = 25;
40 LookupTable NodeLattice::dist_heuristic_lookup_table;
41 
42 // Each of these tables are the projected motion models through
43 // time and space applied to the search on the current node in
44 // continuous map-coordinates (e.g. not meters but partial map cells)
45 // Currently, these are set to project *at minimum* into a neighboring
46 // cell. Though this could be later modified to project a certain
47 // amount of time or particular distance forward.
48 void LatticeMotionTable::initMotionModel(
49  unsigned int & size_x_in,
50  SearchInfo & search_info)
51 {
52  size_x = size_x_in;
53  change_penalty = search_info.change_penalty;
54  non_straight_penalty = search_info.non_straight_penalty;
55  cost_penalty = search_info.cost_penalty;
56  reverse_penalty = search_info.reverse_penalty;
57  travel_distance_reward = 1.0f - search_info.retrospective_penalty;
58  allow_reverse_expansion = search_info.allow_reverse_expansion;
59  rotation_penalty = search_info.rotation_penalty;
60  min_turning_radius = search_info.minimum_turning_radius;
61 
62  if (current_lattice_filepath == search_info.lattice_filepath) {
63  return;
64  }
65  current_lattice_filepath = search_info.lattice_filepath;
66 
67  // Get the metadata about this minimum control set
68  lattice_metadata = getLatticeMetadata(current_lattice_filepath);
69  std::ifstream latticeFile(current_lattice_filepath);
70  if (!latticeFile.is_open()) {
71  throw std::runtime_error("Could not open lattice file");
72  }
73  nlohmann::json json;
74  latticeFile >> json;
75  num_angle_quantization = lattice_metadata.number_of_headings;
76 
77  if (!state_space) {
78  if (!allow_reverse_expansion) {
79  state_space = std::make_shared<ompl::base::DubinsStateSpace>(
80  lattice_metadata.min_turning_radius);
81  motion_model = MotionModel::DUBIN;
82  } else {
83  state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
84  lattice_metadata.min_turning_radius);
85  motion_model = MotionModel::REEDS_SHEPP;
86  }
87  }
88 
89  // Populate the motion primitives at each heading angle
90  float prev_start_angle = 0.0;
91  std::vector<MotionPrimitive> primitives;
92  nlohmann::json json_primitives = json["primitives"];
93  for (unsigned int i = 0; i < json_primitives.size(); ++i) {
94  MotionPrimitive new_primitive;
95  fromJsonToMotionPrimitive(json_primitives[i], new_primitive);
96 
97  if (prev_start_angle != new_primitive.start_angle) {
98  motion_primitives.push_back(primitives);
99  primitives.clear();
100  prev_start_angle = new_primitive.start_angle;
101  }
102  primitives.push_back(new_primitive);
103  }
104  motion_primitives.push_back(primitives);
105 
106  // Populate useful precomputed values to be leveraged
107  trig_values.reserve(lattice_metadata.number_of_headings);
108  for (unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) {
109  trig_values.emplace_back(
110  cos(lattice_metadata.heading_angles[i]),
111  sin(lattice_metadata.heading_angles[i]));
112  }
113 }
114 
115 MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(
116  const NodeLattice * node,
117  unsigned int & direction_change_index)
118 {
119  MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta];
120  MotionPrimitivePtrs primitive_projection_list;
121  for (unsigned int i = 0; i != prims_at_heading.size(); i++) {
122  primitive_projection_list.push_back(&prims_at_heading[i]);
123  }
124 
125  // direction change index
126  direction_change_index = static_cast<unsigned int>(primitive_projection_list.size());
127 
128  if (allow_reverse_expansion) {
129  // Find normalized heading bin of the reverse expansion
130  double reserve_heading = node->pose.theta - (num_angle_quantization / 2);
131  if (reserve_heading < 0) {
132  reserve_heading += num_angle_quantization;
133  }
134  if (reserve_heading > num_angle_quantization) {
135  reserve_heading -= num_angle_quantization;
136  }
137 
138  MotionPrimitives & prims_at_reverse_heading = motion_primitives[reserve_heading];
139  for (unsigned int i = 0; i != prims_at_reverse_heading.size(); i++) {
140  primitive_projection_list.push_back(&prims_at_reverse_heading[i]);
141  }
142  }
143 
144  return primitive_projection_list;
145 }
146 
147 LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & lattice_filepath)
148 {
149  std::ifstream lattice_file(lattice_filepath);
150  if (!lattice_file.is_open()) {
151  throw std::runtime_error("Could not open lattice file!");
152  }
153 
154  nlohmann::json j;
155  lattice_file >> j;
156  LatticeMetadata metadata;
157  fromJsonToMetaData(j["lattice_metadata"], metadata);
158  return metadata;
159 }
160 
161 unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta)
162 {
163  float min_dist = std::numeric_limits<float>::max();
164  unsigned int closest_idx = 0;
165  float dist = 0.0;
166  for (unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) {
167  dist = fabs(angles::shortest_angular_distance(theta, lattice_metadata.heading_angles[i]));
168  if (dist < min_dist) {
169  min_dist = dist;
170  closest_idx = i;
171  }
172  }
173  return closest_idx;
174 }
175 
176 float & LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx)
177 {
178  return lattice_metadata.heading_angles[bin_idx];
179 }
180 
181 double LatticeMotionTable::getAngle(const double & theta)
182 {
183  return getClosestAngularBin(theta);
184 }
185 
186 NodeLattice::NodeLattice(const uint64_t index)
187 : parent(nullptr),
188  pose(0.0f, 0.0f, 0.0f),
189  _cell_cost(std::numeric_limits<float>::quiet_NaN()),
190  _accumulated_cost(std::numeric_limits<float>::max()),
191  _index(index),
192  _was_visited(false),
193  _motion_primitive(nullptr),
194  _backwards(false),
195  _is_node_valid(false)
196 {
197 }
198 
200 {
201  parent = nullptr;
202 }
203 
205 {
206  parent = nullptr;
207  _cell_cost = std::numeric_limits<float>::quiet_NaN();
208  _accumulated_cost = std::numeric_limits<float>::max();
209  _was_visited = false;
210  pose.x = 0.0f;
211  pose.y = 0.0f;
212  pose.theta = 0.0f;
213  _motion_primitive = nullptr;
214  _backwards = false;
215  _is_node_valid = false;
216 }
217 
219  const bool & traverse_unknown,
220  GridCollisionChecker * collision_checker,
221  MotionPrimitive * motion_primitive,
222  bool is_backwards)
223 {
224  // Already found, we can return the result
225  if (!std::isnan(_cell_cost)) {
226  return _is_node_valid;
227  }
228 
229  // Check primitive end pose
230  // Convert grid quantization of primitives to radians, then collision checker quantization
231  static const double bin_size = 2.0 * M_PI / collision_checker->getPrecomputedAngles().size();
232  const double angle = std::fmod(motion_table.getAngleFromBin(this->pose.theta),
233  2.0 * M_PI) / bin_size;
234  if (collision_checker->inCollision(
235  this->pose.x, this->pose.y, angle /*bin in collision checker*/, traverse_unknown))
236  {
237  _is_node_valid = false;
238  _cell_cost = collision_checker->getCost();
239  return false;
240  }
241 
242  // Set the cost of a node to the highest cost across the primitive
243  float max_cell_cost = collision_checker->getCost();
244 
245  // If valid motion primitives are set, check intermediary poses > 1 cell apart
246  if (motion_primitive) {
247  const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
248  const float & resolution_diag_sq = 2.0 * grid_resolution * grid_resolution;
249  MotionPose last_pose(1e9, 1e9, 1e9, TurnDirection::UNKNOWN);
250  MotionPose pose_dist(0.0, 0.0, 0.0, TurnDirection::UNKNOWN);
251 
252  // Back out the initial node starting point to move motion primitive relative to
253  MotionPose initial_pose, prim_pose;
254  initial_pose._x = this->pose.x - (motion_primitive->poses.back()._x / grid_resolution);
255  initial_pose._y = this->pose.y - (motion_primitive->poses.back()._y / grid_resolution);
256  initial_pose._theta = motion_table.getAngleFromBin(motion_primitive->start_angle);
257 
258  for (auto it = motion_primitive->poses.begin(); it != motion_primitive->poses.end(); ++it) {
259  // poses are in metric coordinates from (0, 0), not grid space yet
260  pose_dist = *it - last_pose;
261  // Avoid square roots by (hypot(x, y) > res) == (x*x+y*y > diag*diag)
262  if (pose_dist._x * pose_dist._x + pose_dist._y * pose_dist._y > resolution_diag_sq) {
263  last_pose = *it;
264  // Convert primitive pose into grid space if it should be checked
265  prim_pose._x = initial_pose._x + (it->_x / grid_resolution);
266  prim_pose._y = initial_pose._y + (it->_y / grid_resolution);
267  // If reversing, invert the angle because the robot is backing into the primitive
268  // not driving forward with it
269  if (is_backwards) {
270  prim_pose._theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
271  } else {
272  prim_pose._theta = std::fmod(it->_theta, 2.0 * M_PI);
273  }
274  if (collision_checker->inCollision(
275  prim_pose._x,
276  prim_pose._y,
277  prim_pose._theta / bin_size /*bin in collision checker*/,
278  traverse_unknown))
279  {
280  _is_node_valid = false;
281  _cell_cost = std::max(max_cell_cost, collision_checker->getCost());
282  return false;
283  }
284  max_cell_cost = std::max(max_cell_cost, collision_checker->getCost());
285  }
286  }
287  }
288 
289  _cell_cost = max_cell_cost;
290  _is_node_valid = true;
291  return _is_node_valid;
292 }
293 
295 {
296  const float normalized_cost = child->getCost() / 252.0;
297  if (std::isnan(normalized_cost)) {
298  throw std::runtime_error(
299  "Node attempted to get traversal "
300  "cost without a known collision cost!");
301  }
302 
303  // this is the first node
304  MotionPrimitive * prim = this->getMotionPrimitive();
305  MotionPrimitive * transition_prim = child->getMotionPrimitive();
306  const float prim_length =
307  transition_prim->trajectory_length / motion_table.lattice_metadata.grid_resolution;
308  if (prim == nullptr) {
309  return prim_length;
310  }
311 
312  // Pure rotation in place 1 angular bin in either direction
313  if (transition_prim->trajectory_length < 1e-4) {
314  return motion_table.rotation_penalty * (1.0 + motion_table.cost_penalty * normalized_cost);
315  }
316 
317  float travel_cost = 0.0;
318  float travel_cost_raw = prim_length *
319  (motion_table.travel_distance_reward + motion_table.cost_penalty * normalized_cost);
320 
321  if (transition_prim->arc_length < 0.001) {
322  // New motion is a straight motion, no additional costs to be applied
323  travel_cost = travel_cost_raw;
324  } else {
325  if (prim->left_turn == transition_prim->left_turn) {
326  // Turning motion but keeps in same general direction: encourages to commit to actions
327  travel_cost = travel_cost_raw * motion_table.non_straight_penalty;
328  } else {
329  // Turning motion and velocity directions: penalizes wiggling.
330  travel_cost = travel_cost_raw *
331  (motion_table.non_straight_penalty + motion_table.change_penalty);
332  }
333  }
334 
335  // If backwards flag is set, this primitive is moving in reverse
336  if (child->isBackward()) {
337  // reverse direction
338  travel_cost *= motion_table.reverse_penalty;
339  }
340 
341  return travel_cost;
342 }
343 
345  const Coordinates & node_coords,
346  const Coordinates & goal_coords)
347 {
348  // get obstacle heuristic value
349  const float obstacle_heuristic = getObstacleHeuristic(
350  node_coords, goal_coords, motion_table.cost_penalty);
351  const float distance_heuristic =
352  getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic);
353  return std::max(obstacle_heuristic, distance_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  if (motion_model != MotionModel::STATE_LATTICE) {
364  throw std::runtime_error(
365  "Invalid motion model for Lattice node. Please select"
366  " STATE_LATTICE and provide a valid lattice file.");
367  }
368 
369  motion_table.initMotionModel(size_x, search_info);
370 }
371 
373  const Coordinates & node_coords,
374  const Coordinates & goal_coords,
375  const float & obstacle_heuristic)
376 {
377  // rotate and translate node_coords such that goal_coords relative is (0,0,0)
378  // Due to the rounding involved in exact cell increments for caching,
379  // this is not an exact replica of a live heuristic, but has bounded error.
380  // (Usually less than 1 cell length)
381 
382  // This angle is negative since we are de-rotating the current node
383  // by the goal angle; cos(-th) = cos(th) & sin(-th) = -sin(th)
384  const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
385  const float cos_th = trig_vals.first;
386  const float sin_th = -trig_vals.second;
387  const float dx = node_coords.x - goal_coords.x;
388  const float dy = node_coords.y - goal_coords.y;
389 
390  double dtheta_bin = node_coords.theta - goal_coords.theta;
391  if (dtheta_bin < 0) {
392  dtheta_bin += motion_table.num_angle_quantization;
393  }
394  if (dtheta_bin > motion_table.num_angle_quantization) {
395  dtheta_bin -= motion_table.num_angle_quantization;
396  }
397 
398  Coordinates node_coords_relative(
399  round(dx * cos_th - dy * sin_th),
400  round(dx * sin_th + dy * cos_th),
401  round(dtheta_bin));
402 
403  // Check if the relative node coordinate is within the localized window around the goal
404  // to apply the distance heuristic. Since the lookup table is contains only the positive
405  // X axis, we mirror the Y and theta values across the X axis to find the heuristic values.
406  float motion_heuristic = 0.0;
407  const int floored_size = floor(size_lookup / 2.0);
408  const int ceiling_size = ceil(size_lookup / 2.0);
409  const float mirrored_relative_y = abs(node_coords_relative.y);
410  if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
411  // Need to mirror angle if Y coordinate was mirrored
412  int theta_pos;
413  if (node_coords_relative.y < 0.0) {
414  theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
415  } else {
416  theta_pos = node_coords_relative.theta;
417  }
418  const int x_pos = node_coords_relative.x + floored_size;
419  const int y_pos = static_cast<int>(mirrored_relative_y);
420  const int index =
421  x_pos * ceiling_size * motion_table.num_angle_quantization +
422  y_pos * motion_table.num_angle_quantization +
423  theta_pos;
424  motion_heuristic = dist_heuristic_lookup_table[index];
425  } else if (obstacle_heuristic == 0.0) {
426  static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
427  to[0] = goal_coords.x;
428  to[1] = goal_coords.y;
429  to[2] = motion_table.getAngleFromBin(goal_coords.theta);
430  from[0] = node_coords.x;
431  from[1] = node_coords.y;
432  from[2] = motion_table.getAngleFromBin(node_coords.theta);
433  motion_heuristic = motion_table.state_space->distance(from(), to());
434  }
435 
436  return motion_heuristic;
437 }
438 
440  const float & lookup_table_dim,
441  const MotionModel & /*motion_model*/,
442  const unsigned int & dim_3_size,
443  const SearchInfo & search_info)
444 {
445  // Dubin or Reeds-Shepp shortest distances
446  if (!search_info.allow_reverse_expansion) {
447  motion_table.state_space = std::make_shared<ompl::base::DubinsStateSpace>(
448  search_info.minimum_turning_radius);
449  motion_table.motion_model = MotionModel::DUBIN;
450  } else {
451  motion_table.state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
452  search_info.minimum_turning_radius);
453  motion_table.motion_model = MotionModel::REEDS_SHEPP;
454  }
455  motion_table.lattice_metadata =
456  LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath);
457 
458  ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
459  to[0] = 0.0;
460  to[1] = 0.0;
461  to[2] = 0.0;
462  size_lookup = lookup_table_dim;
463  float motion_heuristic = 0.0;
464  unsigned int index = 0;
465  int dim_3_size_int = static_cast<int>(dim_3_size);
466 
467  // Create a lookup table of Dubin/Reeds-Shepp distances in a window around the goal
468  // to help drive the search towards admissible approaches. Deu to symmetries in the
469  // Heuristic space, we need to only store 2 of the 4 quadrants and simply mirror
470  // around the X axis any relative node lookup. This reduces memory overhead and increases
471  // the size of a window a platform can store in memory.
472  dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
473  for (float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
474  for (float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
475  for (int heading = 0; heading != dim_3_size_int; heading++) {
476  from[0] = x;
477  from[1] = y;
478  from[2] = motion_table.getAngleFromBin(heading);
479  motion_heuristic = motion_table.state_space->distance(from(), to());
480  dist_heuristic_lookup_table[index] = motion_heuristic;
481  index++;
482  }
483  }
484  }
485 }
486 
488  std::function<bool(const uint64_t &,
489  nav2_smac_planner::NodeLattice * &)> & NeighborGetter,
490  GridCollisionChecker * collision_checker,
491  const bool & traverse_unknown,
492  NodeVector & neighbors)
493 {
494  uint64_t index = 0;
495  bool backwards = false;
496  NodePtr neighbor = nullptr;
497  Coordinates initial_node_coords, motion_projection;
498  unsigned int direction_change_index = 0;
499  MotionPrimitivePtrs motion_primitives = motion_table.getMotionPrimitives(
500  this,
501  direction_change_index);
502  const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
503 
504  for (unsigned int i = 0; i != motion_primitives.size(); i++) {
505  const MotionPose & end_pose = motion_primitives[i]->poses.back();
506  motion_projection.x = this->pose.x + (end_pose._x / grid_resolution);
507  motion_projection.y = this->pose.y + (end_pose._y / grid_resolution);
508  motion_projection.theta = motion_primitives[i]->end_angle /*this is the ending angular bin*/;
509 
510  // if i >= idx, then we're in a reversing primitive. In that situation,
511  // the orientation of the robot is mirrored from what it would otherwise
512  // appear to be from the motion primitives file. We want to take this into
513  // account in case the robot base footprint is asymmetric.
514  backwards = false;
515  if (i >= direction_change_index) {
516  backwards = true;
517  float opposite_heading_theta =
518  motion_projection.theta - (motion_table.num_angle_quantization / 2);
519  if (opposite_heading_theta < 0) {
520  opposite_heading_theta += motion_table.num_angle_quantization;
521  }
522  if (opposite_heading_theta > motion_table.num_angle_quantization) {
523  opposite_heading_theta -= motion_table.num_angle_quantization;
524  }
525  motion_projection.theta = opposite_heading_theta;
526  }
527 
528  index = NodeLattice::getIndex(
529  static_cast<unsigned int>(motion_projection.x),
530  static_cast<unsigned int>(motion_projection.y),
531  static_cast<unsigned int>(motion_projection.theta));
532 
533  if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) {
534  // Cache the initial pose in case it was visited but valid
535  // don't want to disrupt continuous coordinate expansion
536  initial_node_coords = neighbor->pose;
537 
538  neighbor->setPose(
539  Coordinates(
540  motion_projection.x,
541  motion_projection.y,
542  motion_projection.theta));
543 
544  // Using a special isNodeValid API here, giving the motion primitive to use to
545  // validity check the transition of the current node to the new node over
546  if (neighbor->isNodeValid(
547  traverse_unknown, collision_checker, motion_primitives[i], backwards))
548  {
549  neighbor->setMotionPrimitive(motion_primitives[i]);
550  // Marking if this search was obtained in the reverse direction
551  neighbor->backwards(backwards);
552  neighbors.push_back(neighbor);
553  } else {
554  neighbor->setPose(initial_node_coords);
555  }
556  }
557  }
558 }
559 
560 bool NodeLattice::backtracePath(CoordinateVector & path)
561 {
562  if (!this->parent) {
563  return false;
564  }
565 
566  NodePtr current_node = this;
567 
568  while (current_node->parent) {
569  addNodeToPath(current_node, path);
570  current_node = current_node->parent;
571  }
572 
573  // add start to path
574  addNodeToPath(current_node, path);
575 
576  return true;
577 }
578 
580  NodeLattice::NodePtr current_node,
581  NodeLattice::CoordinateVector & path)
582 {
583  Coordinates initial_pose, prim_pose;
584  MotionPrimitive * prim = nullptr;
585  const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution;
586  prim = current_node->getMotionPrimitive();
587  // if motion primitive is valid, then was searched (rather than analytically expanded),
588  // include dense path of subpoints making up the primitive at grid resolution
589  if (prim) {
590  initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution);
591  initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution);
592  initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle);
593 
594  for (auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) {
595  // Convert primitive pose into grid space if it should be checked
596  prim_pose.x = initial_pose.x + (it->_x / grid_resolution);
597  prim_pose.y = initial_pose.y + (it->_y / grid_resolution);
598  // If reversing, invert the angle because the robot is backing into the primitive
599  // not driving forward with it
600  if (current_node->isBackward()) {
601  prim_pose.theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
602  } else {
603  prim_pose.theta = it->_theta;
604  }
605  path.push_back(prim_pose);
606  }
607  } else {
608  // For analytic expansion nodes where there is no valid motion primitive
609  path.push_back(current_node->pose);
610  path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta);
611  }
612 }
613 
614 } // 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.
std::vector< float > & getPrecomputedAngles()
Get the angles of the precomputed footprint orientations.
float getCost()
Get cost at footprint pose in costmap.
NodeLattice implementation for graph, Hybrid-A*.
void getNeighbors(std::function< bool(const uint64_t &, nav2_smac_planner::NodeLattice *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
void backwards(bool back=true)
Sets that this primitive is moving in reverse.
uint64_t getIndex()
Gets cell index.
~NodeLattice()
A destructor for nav2_smac_planner::NodeLattice.
float getCost()
Gets the costmap cost at this node.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates)
Get cost of heuristic of node.
void reset()
Reset method for new search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker, MotionPrimitive *primitive=nullptr, bool is_backwards=false)
Check if this node is valid.
void addNodeToPath(NodePtr current_node, CoordinateVector &path)
add node to the path
bool isBackward()
Gets if this primitive is moving in reverse.
bool wasVisited()
Gets if cell has been visited 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.
MotionPrimitive *& getMotionPrimitive()
Gets the motion primitive used to achieve node in search.
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.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
void setMotionPrimitive(MotionPrimitive *prim)
Sets the motion primitive used to achieve node in search.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
A struct of all lattice metadata.
Definition: types.hpp:165
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
void initMotionModel(unsigned int &size_x_in, SearchInfo &search_info)
Initializing state lattice planner's motion model.
MotionPrimitivePtrs getMotionPrimitives(const NodeLattice *node, unsigned int &direction_change_index)
Get projections of motion models.
float & getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
A struct for poses in motion primitives.
Definition: types.hpp:129
A struct of all motion primitive data.
Definition: types.hpp:179
NodeHybrid implementation of coordinate structure.
Search properties and penalties.
Definition: types.hpp:36