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