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