Nav2 Navigation Stack - kilted  kilted
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 <algorithm>
16 #include <chrono>
17 #include <cmath>
18 #include <fstream>
19 #include <limits>
20 #include <memory>
21 #include <queue>
22 #include <string>
23 #include <vector>
24 
25 #include "angles/angles.h"
26 
27 #include "ompl/base/ScopedState.h"
28 #include "ompl/base/spaces/DubinsStateSpace.h"
29 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
30 
31 #include "nav2_smac_planner/node_lattice.hpp"
32 
33 using namespace std::chrono; // NOLINT
34 
35 namespace nav2_smac_planner
36 {
37 
38 // defining static member for all instance to share
39 LatticeMotionTable NodeLattice::motion_table;
40 float NodeLattice::size_lookup = 25;
41 LookupTable NodeLattice::dist_heuristic_lookup_table;
42 
43 // Each of these tables are the projected motion models through
44 // time and space applied to the search on the current node in
45 // continuous map-coordinates (e.g. not meters but partial map cells)
46 // Currently, these are set to project *at minimum* into a neighboring
47 // cell. Though this could be later modified to project a certain
48 // amount of time or particular distance forward.
49 void LatticeMotionTable::initMotionModel(
50  unsigned int & size_x_in,
51  SearchInfo & search_info)
52 {
53  size_x = size_x_in;
54  change_penalty = search_info.change_penalty;
55  non_straight_penalty = search_info.non_straight_penalty;
56  cost_penalty = search_info.cost_penalty;
57  reverse_penalty = search_info.reverse_penalty;
58  travel_distance_reward = 1.0f - search_info.retrospective_penalty;
59  allow_reverse_expansion = search_info.allow_reverse_expansion;
60  rotation_penalty = search_info.rotation_penalty;
61  min_turning_radius = search_info.minimum_turning_radius;
62 
63  if (current_lattice_filepath == search_info.lattice_filepath) {
64  return;
65  }
66  current_lattice_filepath = search_info.lattice_filepath;
67 
68  // Get the metadata about this minimum control set
69  lattice_metadata = getLatticeMetadata(current_lattice_filepath);
70  std::ifstream latticeFile(current_lattice_filepath);
71  if (!latticeFile.is_open()) {
72  throw std::runtime_error("Could not open lattice file");
73  }
74  nlohmann::json json;
75  latticeFile >> json;
76  num_angle_quantization = lattice_metadata.number_of_headings;
77 
78  if (!state_space) {
79  if (!allow_reverse_expansion) {
80  state_space = std::make_shared<ompl::base::DubinsStateSpace>(
81  lattice_metadata.min_turning_radius);
82  motion_model = MotionModel::DUBIN;
83  } else {
84  state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
85  lattice_metadata.min_turning_radius);
86  motion_model = MotionModel::REEDS_SHEPP;
87  }
88  }
89 
90  // Populate the motion primitives at each heading angle
91  float prev_start_angle = 0.0;
92  std::vector<MotionPrimitive> primitives;
93  nlohmann::json json_primitives = json["primitives"];
94  for (unsigned int i = 0; i < json_primitives.size(); ++i) {
95  MotionPrimitive new_primitive;
96  fromJsonToMotionPrimitive(json_primitives[i], new_primitive);
97 
98  if (prev_start_angle != new_primitive.start_angle) {
99  motion_primitives.push_back(primitives);
100  primitives.clear();
101  prev_start_angle = new_primitive.start_angle;
102  }
103  primitives.push_back(new_primitive);
104  }
105  motion_primitives.push_back(primitives);
106 
107  // Populate useful precomputed values to be leveraged
108  trig_values.reserve(lattice_metadata.number_of_headings);
109  for (unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) {
110  trig_values.emplace_back(
111  cos(lattice_metadata.heading_angles[i]),
112  sin(lattice_metadata.heading_angles[i]));
113  }
114 }
115 
116 MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(
117  const NodeLattice * node,
118  unsigned int & direction_change_index)
119 {
120  MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta];
121  MotionPrimitivePtrs primitive_projection_list;
122  for (unsigned int i = 0; i != prims_at_heading.size(); i++) {
123  primitive_projection_list.push_back(&prims_at_heading[i]);
124  }
125 
126  // direction change index
127  direction_change_index = static_cast<unsigned int>(primitive_projection_list.size());
128 
129  if (allow_reverse_expansion) {
130  // Find normalized heading bin of the reverse expansion
131  double reserve_heading = node->pose.theta - (num_angle_quantization / 2);
132  if (reserve_heading < 0) {
133  reserve_heading += num_angle_quantization;
134  }
135  if (reserve_heading > num_angle_quantization) {
136  reserve_heading -= num_angle_quantization;
137  }
138 
139  MotionPrimitives & prims_at_reverse_heading = motion_primitives[reserve_heading];
140  for (unsigned int i = 0; i != prims_at_reverse_heading.size(); i++) {
141  primitive_projection_list.push_back(&prims_at_reverse_heading[i]);
142  }
143  }
144 
145  return primitive_projection_list;
146 }
147 
148 LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & lattice_filepath)
149 {
150  std::ifstream lattice_file(lattice_filepath);
151  if (!lattice_file.is_open()) {
152  throw std::runtime_error("Could not open lattice file!");
153  }
154 
155  nlohmann::json j;
156  lattice_file >> j;
157  LatticeMetadata metadata;
158  fromJsonToMetaData(j["lattice_metadata"], metadata);
159  return metadata;
160 }
161 
162 unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta)
163 {
164  float min_dist = std::numeric_limits<float>::max();
165  unsigned int closest_idx = 0;
166  float dist = 0.0;
167  for (unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) {
168  dist = fabs(angles::shortest_angular_distance(theta, lattice_metadata.heading_angles[i]));
169  if (dist < min_dist) {
170  min_dist = dist;
171  closest_idx = i;
172  }
173  }
174  return closest_idx;
175 }
176 
177 float & LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx)
178 {
179  return lattice_metadata.heading_angles[bin_idx];
180 }
181 
182 double LatticeMotionTable::getAngle(const double & theta)
183 {
184  return getClosestAngularBin(theta);
185 }
186 
187 NodeLattice::NodeLattice(const uint64_t index)
188 : parent(nullptr),
189  pose(0.0f, 0.0f, 0.0f),
190  _cell_cost(std::numeric_limits<float>::quiet_NaN()),
191  _accumulated_cost(std::numeric_limits<float>::max()),
192  _index(index),
193  _was_visited(false),
194  _motion_primitive(nullptr),
195  _backwards(false),
196  _is_node_valid(false)
197 {
198 }
199 
201 {
202  parent = nullptr;
203 }
204 
206 {
207  parent = nullptr;
208  _cell_cost = std::numeric_limits<float>::quiet_NaN();
209  _accumulated_cost = std::numeric_limits<float>::max();
210  _was_visited = false;
211  pose.x = 0.0f;
212  pose.y = 0.0f;
213  pose.theta = 0.0f;
214  _motion_primitive = nullptr;
215  _backwards = false;
216  _is_node_valid = false;
217 }
218 
220  const bool & traverse_unknown,
221  GridCollisionChecker * collision_checker,
222  MotionPrimitive * motion_primitive,
223  bool is_backwards)
224 {
225  // Already found, we can return the result
226  if (!std::isnan(_cell_cost)) {
227  return _is_node_valid;
228  }
229 
230  // Check primitive end pose
231  // Convert grid quantization of primitives to radians, then collision checker quantization
232  static const double bin_size = 2.0 * M_PI / collision_checker->getPrecomputedAngles().size();
233  const double angle = std::fmod(motion_table.getAngleFromBin(this->pose.theta),
234  2.0 * M_PI) / 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 = std::fmod(it->_theta, 2.0 * M_PI);
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 CoordinateVector & goals_coords)
348 {
349  // get obstacle heuristic value
350  // obstacle heuristic does not depend on goal heading
351  const float obstacle_heuristic = getObstacleHeuristic(
352  node_coords, goals_coords[0], motion_table.cost_penalty);
353  float distance_heuristic = std::numeric_limits<float>::max();
354  for (unsigned int i = 0; i < goals_coords.size(); i++) {
355  distance_heuristic = std::min(
356  distance_heuristic,
357  getDistanceHeuristic(node_coords, goals_coords[i], obstacle_heuristic));
358  }
359  return std::max(obstacle_heuristic, distance_heuristic);
360 }
361 
363  const MotionModel & motion_model,
364  unsigned int & size_x,
365  unsigned int & /*size_y*/,
366  unsigned int & /*num_angle_quantization*/,
367  SearchInfo & search_info)
368 {
369  if (motion_model != MotionModel::STATE_LATTICE) {
370  throw std::runtime_error(
371  "Invalid motion model for Lattice node. Please select"
372  " STATE_LATTICE and provide a valid lattice file.");
373  }
374 
375  motion_table.initMotionModel(size_x, search_info);
376 }
377 
379  const Coordinates & node_coords,
380  const Coordinates & goal_coords,
381  const float & obstacle_heuristic)
382 {
383  // rotate and translate node_coords such that goal_coords relative is (0,0,0)
384  // Due to the rounding involved in exact cell increments for caching,
385  // this is not an exact replica of a live heuristic, but has bounded error.
386  // (Usually less than 1 cell length)
387 
388  // This angle is negative since we are de-rotating the current node
389  // by the goal angle; cos(-th) = cos(th) & sin(-th) = -sin(th)
390  const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
391  const float cos_th = trig_vals.first;
392  const float sin_th = -trig_vals.second;
393  const float dx = node_coords.x - goal_coords.x;
394  const float dy = node_coords.y - goal_coords.y;
395 
396  double dtheta_bin = node_coords.theta - goal_coords.theta;
397  if (dtheta_bin < 0) {
398  dtheta_bin += motion_table.num_angle_quantization;
399  }
400  if (dtheta_bin > motion_table.num_angle_quantization) {
401  dtheta_bin -= motion_table.num_angle_quantization;
402  }
403 
404  Coordinates node_coords_relative(
405  round(dx * cos_th - dy * sin_th),
406  round(dx * sin_th + dy * cos_th),
407  round(dtheta_bin));
408 
409  // Check if the relative node coordinate is within the localized window around the goal
410  // to apply the distance heuristic. Since the lookup table is contains only the positive
411  // X axis, we mirror the Y and theta values across the X axis to find the heuristic values.
412  float motion_heuristic = 0.0;
413  const int floored_size = floor(size_lookup / 2.0);
414  const int ceiling_size = ceil(size_lookup / 2.0);
415  const float mirrored_relative_y = abs(node_coords_relative.y);
416  if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
417  // Need to mirror angle if Y coordinate was mirrored
418  int theta_pos;
419  if (node_coords_relative.y < 0.0) {
420  theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
421  } else {
422  theta_pos = node_coords_relative.theta;
423  }
424  const int x_pos = node_coords_relative.x + floored_size;
425  const int y_pos = static_cast<int>(mirrored_relative_y);
426  const int index =
427  x_pos * ceiling_size * motion_table.num_angle_quantization +
428  y_pos * motion_table.num_angle_quantization +
429  theta_pos;
430  motion_heuristic = dist_heuristic_lookup_table[index];
431  } else if (obstacle_heuristic == 0.0) {
432  static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
433  to[0] = goal_coords.x;
434  to[1] = goal_coords.y;
435  to[2] = motion_table.getAngleFromBin(goal_coords.theta);
436  from[0] = node_coords.x;
437  from[1] = node_coords.y;
438  from[2] = motion_table.getAngleFromBin(node_coords.theta);
439  motion_heuristic = motion_table.state_space->distance(from(), to());
440  }
441 
442  return motion_heuristic;
443 }
444 
446  const float & lookup_table_dim,
447  const MotionModel & /*motion_model*/,
448  const unsigned int & dim_3_size,
449  const SearchInfo & search_info)
450 {
451  // Dubin or Reeds-Shepp shortest distances
452  if (!search_info.allow_reverse_expansion) {
453  motion_table.state_space = std::make_shared<ompl::base::DubinsStateSpace>(
454  search_info.minimum_turning_radius);
455  motion_table.motion_model = MotionModel::DUBIN;
456  } else {
457  motion_table.state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
458  search_info.minimum_turning_radius);
459  motion_table.motion_model = MotionModel::REEDS_SHEPP;
460  }
461  motion_table.lattice_metadata =
462  LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath);
463 
464  ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
465  to[0] = 0.0;
466  to[1] = 0.0;
467  to[2] = 0.0;
468  size_lookup = lookup_table_dim;
469  float motion_heuristic = 0.0;
470  unsigned int index = 0;
471  int dim_3_size_int = static_cast<int>(dim_3_size);
472 
473  // Create a lookup table of Dubin/Reeds-Shepp distances in a window around the goal
474  // to help drive the search towards admissible approaches. Due to symmetries in the
475  // Heuristic space, we need to only store 2 of the 4 quadrants and simply mirror
476  // around the X axis any relative node lookup. This reduces memory overhead and increases
477  // the size of a window a platform can store in memory.
478  dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
479  for (float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
480  for (float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
481  for (int heading = 0; heading != dim_3_size_int; heading++) {
482  from[0] = x;
483  from[1] = y;
484  from[2] = motion_table.getAngleFromBin(heading);
485  motion_heuristic = motion_table.state_space->distance(from(), to());
486  dist_heuristic_lookup_table[index] = motion_heuristic;
487  index++;
488  }
489  }
490  }
491 }
492 
494  std::function<bool(const uint64_t &,
495  nav2_smac_planner::NodeLattice * &)> & NeighborGetter,
496  GridCollisionChecker * collision_checker,
497  const bool & traverse_unknown,
498  NodeVector & neighbors)
499 {
500  uint64_t index = 0;
501  bool backwards = false;
502  NodePtr neighbor = nullptr;
503  Coordinates initial_node_coords, motion_projection;
504  unsigned int direction_change_index = 0;
505  MotionPrimitivePtrs motion_primitives = motion_table.getMotionPrimitives(
506  this,
507  direction_change_index);
508  const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
509 
510  for (unsigned int i = 0; i != motion_primitives.size(); i++) {
511  const MotionPose & end_pose = motion_primitives[i]->poses.back();
512  motion_projection.x = this->pose.x + (end_pose._x / grid_resolution);
513  motion_projection.y = this->pose.y + (end_pose._y / grid_resolution);
514  motion_projection.theta = motion_primitives[i]->end_angle /*this is the ending angular bin*/;
515 
516  // if i >= idx, then we're in a reversing primitive. In that situation,
517  // the orientation of the robot is mirrored from what it would otherwise
518  // appear to be from the motion primitives file. We want to take this into
519  // account in case the robot base footprint is asymmetric.
520  backwards = false;
521  if (i >= direction_change_index) {
522  backwards = true;
523  float opposite_heading_theta =
524  motion_projection.theta - (motion_table.num_angle_quantization / 2);
525  if (opposite_heading_theta < 0) {
526  opposite_heading_theta += motion_table.num_angle_quantization;
527  }
528  if (opposite_heading_theta > motion_table.num_angle_quantization) {
529  opposite_heading_theta -= motion_table.num_angle_quantization;
530  }
531  motion_projection.theta = opposite_heading_theta;
532  }
533 
534  index = NodeLattice::getIndex(
535  static_cast<unsigned int>(motion_projection.x),
536  static_cast<unsigned int>(motion_projection.y),
537  static_cast<unsigned int>(motion_projection.theta));
538 
539  if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) {
540  // Cache the initial pose in case it was visited but valid
541  // don't want to disrupt continuous coordinate expansion
542  initial_node_coords = neighbor->pose;
543 
544  neighbor->setPose(
545  Coordinates(
546  motion_projection.x,
547  motion_projection.y,
548  motion_projection.theta));
549 
550  // Using a special isNodeValid API here, giving the motion primitive to use to
551  // validity check the transition of the current node to the new node over
552  if (neighbor->isNodeValid(
553  traverse_unknown, collision_checker, motion_primitives[i], backwards))
554  {
555  neighbor->setMotionPrimitive(motion_primitives[i]);
556  // Marking if this search was obtained in the reverse direction
557  neighbor->backwards(backwards);
558  neighbors.push_back(neighbor);
559  } else {
560  neighbor->setPose(initial_node_coords);
561  }
562  }
563  }
564 }
565 
566 bool NodeLattice::backtracePath(CoordinateVector & path)
567 {
568  if (!this->parent) {
569  return false;
570  }
571 
572  NodePtr current_node = this;
573 
574  while (current_node->parent) {
575  addNodeToPath(current_node, path);
576  current_node = current_node->parent;
577  }
578 
579  // add start to path
580  addNodeToPath(current_node, path);
581 
582  return true;
583 }
584 
586  NodeLattice::NodePtr current_node,
587  NodeLattice::CoordinateVector & path)
588 {
589  Coordinates initial_pose, prim_pose;
590  MotionPrimitive * prim = nullptr;
591  const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution;
592  prim = current_node->getMotionPrimitive();
593  // if motion primitive is valid, then was searched (rather than analytically expanded),
594  // include dense path of subpoints making up the primitive at grid resolution
595  if (prim) {
596  initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution);
597  initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution);
598  initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle);
599 
600  for (auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) {
601  // Convert primitive pose into grid space if it should be checked
602  prim_pose.x = initial_pose.x + (it->_x / grid_resolution);
603  prim_pose.y = initial_pose.y + (it->_y / grid_resolution);
604  // If reversing, invert the angle because the robot is backing into the primitive
605  // not driving forward with it
606  if (current_node->isBackward()) {
607  prim_pose.theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
608  } else {
609  prim_pose.theta = it->_theta;
610  }
611  path.push_back(prim_pose);
612  }
613  } else {
614  // For analytic expansion nodes where there is no valid motion primitive
615  path.push_back(current_node->pose);
616  path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta);
617  }
618 }
619 
620 } // 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.
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.
static float getHeuristicCost(const Coordinates &node_coords, const CoordinateVector &goals_coords)
Get cost of heuristic of node.
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