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