26 #include "ompl/base/ScopedState.h"
27 #include "ompl/base/spaces/DubinsStateSpace.h"
28 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
30 #include "nav2_smac_planner/node_hybrid.hpp"
32 using namespace std::chrono;
34 namespace nav2_smac_planner
38 LookupTable NodeHybrid::obstacle_heuristic_lookup_table;
39 float NodeHybrid::travel_distance_cost = sqrtf(2.0f);
40 HybridMotionTable NodeHybrid::motion_table;
41 float NodeHybrid::size_lookup = 25;
42 LookupTable NodeHybrid::dist_heuristic_lookup_table;
43 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> NodeHybrid::costmap_ros =
nullptr;
45 ObstacleHeuristicQueue NodeHybrid::obstacle_heuristic_queue;
56 void HybridMotionTable::initDubin(
57 unsigned int & size_x_in,
59 unsigned int & num_angle_quantization_in,
63 change_penalty = search_info.change_penalty;
64 non_straight_penalty = search_info.non_straight_penalty;
65 cost_penalty = search_info.cost_penalty;
66 reverse_penalty = search_info.reverse_penalty;
67 travel_distance_reward = 1.0f - search_info.retrospective_penalty;
68 downsample_obstacle_heuristic = search_info.downsample_obstacle_heuristic;
69 use_quadratic_cost_penalty = search_info.use_quadratic_cost_penalty;
72 if (num_angle_quantization_in == num_angle_quantization &&
73 min_turning_radius == search_info.minimum_turning_radius &&
74 motion_model == MotionModel::DUBIN)
79 num_angle_quantization = num_angle_quantization_in;
80 num_angle_quantization_float =
static_cast<float>(num_angle_quantization);
81 min_turning_radius = search_info.minimum_turning_radius;
82 motion_model = MotionModel::DUBIN;
94 float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius));
98 2.0f *
static_cast<float>(M_PI) /
static_cast<float>(num_angle_quantization);
100 if (angle < bin_size) {
105 increments = ceil(angle / bin_size);
107 angle = increments * bin_size;
112 const float delta_x = min_turning_radius * sin(angle);
115 const float delta_y = min_turning_radius - (min_turning_radius * cos(angle));
116 const float delta_dist = hypotf(delta_x, delta_y);
119 projections.reserve(3);
120 projections.emplace_back(delta_dist, 0.0, 0.0, TurnDirection::FORWARD);
121 projections.emplace_back(delta_x, delta_y, increments, TurnDirection::LEFT);
122 projections.emplace_back(delta_x, -delta_y, -increments, TurnDirection::RIGHT);
124 if (search_info.allow_primitive_interpolation && increments > 1.0f) {
128 projections.reserve(3 + (2 * (increments - 1)));
129 for (
unsigned int i = 1; i < static_cast<unsigned int>(increments); i++) {
130 const float angle_n =
static_cast<float>(i) * bin_size;
131 const float turning_rad_n = delta_dist / (2.0f * sin(angle_n / 2.0f));
132 const float delta_x_n = turning_rad_n * sin(angle_n);
133 const float delta_y_n = turning_rad_n - (turning_rad_n * cos(angle_n));
134 projections.emplace_back(
135 delta_x_n, delta_y_n,
static_cast<float>(i), TurnDirection::LEFT);
136 projections.emplace_back(
137 delta_x_n, -delta_y_n, -
static_cast<float>(i), TurnDirection::RIGHT);
142 state_space = std::make_shared<ompl::base::DubinsStateSpace>(min_turning_radius);
145 delta_xs.resize(projections.size());
146 delta_ys.resize(projections.size());
147 trig_values.resize(num_angle_quantization);
149 for (
unsigned int i = 0; i != projections.size(); i++) {
150 delta_xs[i].resize(num_angle_quantization);
151 delta_ys[i].resize(num_angle_quantization);
153 for (
unsigned int j = 0; j != num_angle_quantization; j++) {
154 double cos_theta = cos(bin_size * j);
155 double sin_theta = sin(bin_size * j);
158 trig_values[j] = {cos_theta, sin_theta};
160 delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta;
161 delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta;
166 travel_costs.resize(projections.size());
167 for (
unsigned int i = 0; i != projections.size(); i++) {
168 const TurnDirection turn_dir = projections[i]._turn_dir;
169 if (turn_dir != TurnDirection::FORWARD && turn_dir != TurnDirection::REVERSE) {
171 const float arc_angle = projections[i]._theta * bin_size;
172 const float turning_rad = delta_dist / (2.0f * sin(arc_angle / 2.0f));
173 travel_costs[i] = turning_rad * arc_angle;
175 travel_costs[i] = delta_dist;
183 void HybridMotionTable::initReedsShepp(
184 unsigned int & size_x_in,
186 unsigned int & num_angle_quantization_in,
190 change_penalty = search_info.change_penalty;
191 non_straight_penalty = search_info.non_straight_penalty;
192 cost_penalty = search_info.cost_penalty;
193 reverse_penalty = search_info.reverse_penalty;
194 travel_distance_reward = 1.0f - search_info.retrospective_penalty;
195 downsample_obstacle_heuristic = search_info.downsample_obstacle_heuristic;
196 use_quadratic_cost_penalty = search_info.use_quadratic_cost_penalty;
199 if (num_angle_quantization_in == num_angle_quantization &&
200 min_turning_radius == search_info.minimum_turning_radius &&
201 motion_model == MotionModel::REEDS_SHEPP)
206 num_angle_quantization = num_angle_quantization_in;
207 num_angle_quantization_float =
static_cast<float>(num_angle_quantization);
208 min_turning_radius = search_info.minimum_turning_radius;
209 motion_model = MotionModel::REEDS_SHEPP;
211 float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius));
213 2.0f *
static_cast<float>(M_PI) /
static_cast<float>(num_angle_quantization);
215 if (angle < bin_size) {
218 increments = ceil(angle / bin_size);
220 angle = increments * bin_size;
222 const float delta_x = min_turning_radius * sin(angle);
223 const float delta_y = min_turning_radius - (min_turning_radius * cos(angle));
224 const float delta_dist = hypotf(delta_x, delta_y);
227 projections.reserve(6);
228 projections.emplace_back(delta_dist, 0.0, 0.0, TurnDirection::FORWARD);
229 projections.emplace_back(
230 delta_x, delta_y, increments, TurnDirection::LEFT);
231 projections.emplace_back(
232 delta_x, -delta_y, -increments, TurnDirection::RIGHT);
233 projections.emplace_back(-delta_dist, 0.0, 0.0, TurnDirection::REVERSE);
234 projections.emplace_back(
235 -delta_x, delta_y, -increments, TurnDirection::REV_LEFT);
236 projections.emplace_back(
237 -delta_x, -delta_y, increments, TurnDirection::REV_RIGHT);
239 if (search_info.allow_primitive_interpolation && increments > 1.0f) {
243 projections.reserve(6 + (4 * (increments - 1)));
244 for (
unsigned int i = 1; i < static_cast<unsigned int>(increments); i++) {
245 const float angle_n =
static_cast<float>(i) * bin_size;
246 const float turning_rad_n = delta_dist / (2.0f * sin(angle_n / 2.0f));
247 const float delta_x_n = turning_rad_n * sin(angle_n);
248 const float delta_y_n = turning_rad_n - (turning_rad_n * cos(angle_n));
249 projections.emplace_back(
250 delta_x_n, delta_y_n,
static_cast<float>(i), TurnDirection::LEFT);
251 projections.emplace_back(
252 delta_x_n, -delta_y_n, -
static_cast<float>(i), TurnDirection::RIGHT);
253 projections.emplace_back(
254 -delta_x_n, delta_y_n, -
static_cast<float>(i),
255 TurnDirection::REV_LEFT);
256 projections.emplace_back(
257 -delta_x_n, -delta_y_n,
static_cast<float>(i),
258 TurnDirection::REV_RIGHT);
263 state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(min_turning_radius);
266 delta_xs.resize(projections.size());
267 delta_ys.resize(projections.size());
268 trig_values.resize(num_angle_quantization);
270 for (
unsigned int i = 0; i != projections.size(); i++) {
271 delta_xs[i].resize(num_angle_quantization);
272 delta_ys[i].resize(num_angle_quantization);
274 for (
unsigned int j = 0; j != num_angle_quantization; j++) {
275 double cos_theta = cos(bin_size * j);
276 double sin_theta = sin(bin_size * j);
279 trig_values[j] = {cos_theta, sin_theta};
281 delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta;
282 delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta;
287 travel_costs.resize(projections.size());
288 for (
unsigned int i = 0; i != projections.size(); i++) {
289 const TurnDirection turn_dir = projections[i]._turn_dir;
290 if (turn_dir != TurnDirection::FORWARD && turn_dir != TurnDirection::REVERSE) {
292 const float arc_angle = projections[i]._theta * bin_size;
293 const float turning_rad = delta_dist / (2.0f * sin(arc_angle / 2.0f));
294 travel_costs[i] = turning_rad * arc_angle;
296 travel_costs[i] = delta_dist;
301 MotionPoses HybridMotionTable::getProjections(
const NodeHybrid * node)
303 MotionPoses projection_list;
304 projection_list.reserve(projections.size());
306 for (
unsigned int i = 0; i != projections.size(); i++) {
307 const MotionPose & proj_motion_model = projections[i];
310 const float & node_heading = node->pose.theta;
311 float new_heading = node_heading + proj_motion_model._theta;
313 if (new_heading < 0.0) {
314 new_heading += num_angle_quantization_float;
317 if (new_heading >= num_angle_quantization_float) {
318 new_heading -= num_angle_quantization_float;
321 projection_list.emplace_back(
322 delta_xs[i][node_heading] + node->pose.x,
323 delta_ys[i][node_heading] + node->pose.y,
324 new_heading, proj_motion_model._turn_dir);
327 return projection_list;
330 unsigned int HybridMotionTable::getClosestAngularBin(
const double & theta)
332 auto bin =
static_cast<unsigned int>(round(
static_cast<float>(theta) / bin_size));
333 return bin < num_angle_quantization ? bin : 0u;
336 float HybridMotionTable::getAngleFromBin(
const unsigned int & bin_idx)
338 return bin_idx * bin_size;
341 double HybridMotionTable::getAngle(
const double & theta)
343 return theta / bin_size;
346 NodeHybrid::NodeHybrid(
const uint64_t index)
348 pose(0.0f, 0.0f, 0.0f),
349 _cell_cost(std::numeric_limits<float>::quiet_NaN()),
350 _accumulated_cost(std::numeric_limits<float>::max()),
353 _motion_primitive_index(std::numeric_limits<unsigned int>::max()),
354 _is_node_valid(false)
366 _cell_cost = std::numeric_limits<float>::quiet_NaN();
367 _accumulated_cost = std::numeric_limits<float>::max();
368 _was_visited =
false;
369 _motion_primitive_index = std::numeric_limits<unsigned int>::max();
373 _is_node_valid =
false;
377 const bool & traverse_unknown,
381 if (!std::isnan(_cell_cost)) {
382 return _is_node_valid;
386 this->pose.x, this->pose.y, this->pose.theta , traverse_unknown);
387 _cell_cost = collision_checker->
getCost();
388 return _is_node_valid;
393 const float normalized_cost = child->
getCost() / 252.0f;
394 if (std::isnan(normalized_cost)) {
395 throw std::runtime_error(
396 "Node attempted to get traversal "
397 "cost without a known SE2 collision cost!");
402 return NodeHybrid::travel_distance_cost;
407 float travel_cost = 0.0;
409 if (motion_table.use_quadratic_cost_penalty) {
411 (motion_table.travel_distance_reward +
412 (motion_table.cost_penalty * normalized_cost * normalized_cost));
415 (motion_table.travel_distance_reward + motion_table.cost_penalty * normalized_cost);
418 if (child_turn_dir == TurnDirection::FORWARD || child_turn_dir == TurnDirection::REVERSE) {
420 travel_cost = travel_cost_raw;
424 travel_cost = travel_cost_raw * motion_table.non_straight_penalty;
427 travel_cost = travel_cost_raw *
428 (motion_table.non_straight_penalty + motion_table.change_penalty);
432 if (child_turn_dir == TurnDirection::REV_RIGHT ||
433 child_turn_dir == TurnDirection::REV_LEFT ||
434 child_turn_dir == TurnDirection::REVERSE)
437 travel_cost *= motion_table.reverse_penalty;
445 const CoordinateVector & goals_coords)
448 const float obstacle_heuristic =
450 float distance_heuristic = std::numeric_limits<float>::max();
451 for (
unsigned int i = 0; i < goals_coords.size(); i++) {
452 distance_heuristic = std::min(
456 return std::max(obstacle_heuristic, distance_heuristic);
460 const MotionModel & motion_model,
461 unsigned int & size_x,
462 unsigned int & size_y,
463 unsigned int & num_angle_quantization,
467 switch (motion_model) {
468 case MotionModel::DUBIN:
469 motion_table.
initDubin(size_x, size_y, num_angle_quantization, search_info);
471 case MotionModel::REEDS_SHEPP:
472 motion_table.
initReedsShepp(size_x, size_y, num_angle_quantization, search_info);
475 throw std::runtime_error(
476 "Invalid motion model for Hybrid A*. Please select between"
477 " Dubin (Ackermann forward only),"
478 " Reeds-Shepp (Ackermann forward and back).");
481 travel_distance_cost = motion_table.projections[0]._x;
484 inline float distanceHeuristic2D(
485 const uint64_t idx,
const unsigned int size_x,
486 const unsigned int target_x,
const unsigned int target_y)
488 int dx =
static_cast<int>(idx % size_x) -
static_cast<int>(target_x);
489 int dy =
static_cast<int>(idx / size_x) -
static_cast<int>(target_y);
490 return std::sqrt(dx * dx + dy * dy);
494 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_i,
495 const unsigned int & start_x,
const unsigned int & start_y,
496 const unsigned int & goal_x,
const unsigned int & goal_y)
502 costmap_ros = costmap_ros_i;
503 auto costmap = costmap_ros->getCostmap();
506 unsigned int size = 0u;
507 unsigned int size_x = 0u;
508 if (motion_table.downsample_obstacle_heuristic) {
509 size_x = ceil(
static_cast<float>(costmap->getSizeInCellsX()) / 2.0f);
511 ceil(
static_cast<float>(costmap->getSizeInCellsY()) / 2.0f);
513 size_x = costmap->getSizeInCellsX();
514 size = size_x * costmap->getSizeInCellsY();
517 if (obstacle_heuristic_lookup_table.size() == size) {
520 obstacle_heuristic_lookup_table.begin(),
521 obstacle_heuristic_lookup_table.end(), 0.0f);
523 unsigned int obstacle_size = obstacle_heuristic_lookup_table.size();
524 obstacle_heuristic_lookup_table.resize(size, 0.0f);
527 obstacle_heuristic_lookup_table.begin(), obstacle_size, 0.0f);
530 obstacle_heuristic_queue.clear();
531 obstacle_heuristic_queue.reserve(size);
534 unsigned int goal_index;
535 if (motion_table.downsample_obstacle_heuristic) {
536 goal_index = floor(goal_y / 2.0f) * size_x + floor(goal_x / 2.0f);
538 goal_index = floor(goal_y) * size_x + floor(goal_x);
541 obstacle_heuristic_queue.emplace_back(
542 distanceHeuristic2D(goal_index, size_x, start_x, start_y), goal_index);
546 obstacle_heuristic_lookup_table[goal_index] = -0.00001f;
552 const float & cost_penalty)
555 auto costmap = costmap_ros->getCostmap();
556 unsigned int size_x = 0u;
557 unsigned int size_y = 0u;
558 if (motion_table.downsample_obstacle_heuristic) {
559 size_x = ceil(
static_cast<float>(costmap->getSizeInCellsX()) / 2.0f);
560 size_y = ceil(
static_cast<float>(costmap->getSizeInCellsY()) / 2.0f);
562 size_x = costmap->getSizeInCellsX();
563 size_y = costmap->getSizeInCellsY();
567 unsigned int start_y, start_x;
568 const bool & downsample_H = motion_table.downsample_obstacle_heuristic;
570 start_y = floor(node_coords.y / 2.0f);
571 start_x = floor(node_coords.x / 2.0f);
573 start_y = floor(node_coords.y);
574 start_x = floor(node_coords.x);
577 const unsigned int start_index = start_y * size_x + start_x;
578 const float & requested_node_cost = obstacle_heuristic_lookup_table[start_index];
579 if (requested_node_cost > 0.0f) {
581 return downsample_H ? 2.0f * requested_node_cost : requested_node_cost;
592 for (
auto & n : obstacle_heuristic_queue) {
593 n.first = -obstacle_heuristic_lookup_table[n.second] +
594 distanceHeuristic2D(n.second, size_x, start_x, start_y);
597 obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
600 const int size_x_int =
static_cast<int>(size_x);
601 const float sqrt2 = sqrtf(2.0f);
602 float c_cost, cost, travel_cost, new_cost, existing_cost;
604 unsigned int idx, new_idx = 0;
606 const std::vector<int> neighborhood = {1, -1,
607 size_x_int, -size_x_int,
608 size_x_int + 1, size_x_int - 1,
609 -size_x_int + 1, -size_x_int - 1};
611 while (!obstacle_heuristic_queue.empty()) {
612 idx = obstacle_heuristic_queue.front().second;
614 obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
616 obstacle_heuristic_queue.pop_back();
617 c_cost = obstacle_heuristic_lookup_table[idx];
624 obstacle_heuristic_lookup_table[idx] = c_cost;
627 for (
unsigned int i = 0; i != neighborhood.size(); i++) {
628 new_idx =
static_cast<unsigned int>(
static_cast<int>(idx) + neighborhood[i]);
631 if (new_idx < size_x * size_y) {
634 unsigned int y_offset = (new_idx / size_x) * 2;
635 unsigned int x_offset = (new_idx - ((new_idx / size_x) * size_x)) * 2;
636 cost = costmap->getCost(x_offset, y_offset);
637 for (
unsigned int k = 0; k < 2u; ++k) {
638 unsigned int mxd = x_offset + k;
639 if (mxd >= costmap->getSizeInCellsX()) {
642 for (
unsigned int j = 0; j < 2u; ++j) {
643 unsigned int myd = y_offset + j;
644 if (myd >= costmap->getSizeInCellsY()) {
647 if (k == 0 && j == 0) {
650 cost = std::min(cost,
static_cast<float>(costmap->getCost(mxd, myd)));
654 cost =
static_cast<float>(costmap->getCost(new_idx));
657 if (cost >= INSCRIBED_COST) {
661 my = new_idx / size_x;
662 mx = new_idx - (my * size_x);
664 if (mx >= size_x - 3 || mx <= 3) {
667 if (my >= size_y - 3 || my <= 3) {
671 existing_cost = obstacle_heuristic_lookup_table[new_idx];
672 if (existing_cost <= 0.0f) {
673 if (motion_table.use_quadratic_cost_penalty) {
675 (i <= 3 ? 1.0f : sqrt2) * (1.0f + (cost_penalty * cost * cost / 63504.0f));
678 ((i <= 3) ? 1.0f : sqrt2) * (1.0f + (cost_penalty * cost / 252.0f));
681 new_cost = c_cost + travel_cost;
682 if (existing_cost == 0.0f || -existing_cost > new_cost) {
684 obstacle_heuristic_lookup_table[new_idx] = -new_cost;
685 obstacle_heuristic_queue.emplace_back(
686 new_cost + distanceHeuristic2D(new_idx, size_x, start_x, start_y), new_idx);
688 obstacle_heuristic_queue.begin(), obstacle_heuristic_queue.end(),
695 if (idx == start_index) {
719 return downsample_H ? 2.0f * requested_node_cost : requested_node_cost;
725 const float & obstacle_heuristic)
734 const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
735 const float cos_th = trig_vals.first;
736 const float sin_th = -trig_vals.second;
737 const float dx = node_coords.x - goal_coords.x;
738 const float dy = node_coords.y - goal_coords.y;
740 double dtheta_bin = node_coords.theta - goal_coords.theta;
741 if (dtheta_bin < 0) {
742 dtheta_bin += motion_table.num_angle_quantization;
744 if (dtheta_bin > motion_table.num_angle_quantization) {
745 dtheta_bin -= motion_table.num_angle_quantization;
749 round(dx * cos_th - dy * sin_th),
750 round(dx * sin_th + dy * cos_th),
756 float motion_heuristic = 0.0;
757 const int floored_size = floor(size_lookup / 2.0);
758 const int ceiling_size = ceil(size_lookup / 2.0);
759 const float mirrored_relative_y = abs(node_coords_relative.y);
760 if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
763 if (node_coords_relative.y < 0.0) {
764 theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
766 theta_pos = node_coords_relative.theta;
768 const int x_pos = node_coords_relative.x + floored_size;
769 const int y_pos =
static_cast<int>(mirrored_relative_y);
771 x_pos * ceiling_size * motion_table.num_angle_quantization +
772 y_pos * motion_table.num_angle_quantization +
774 motion_heuristic = dist_heuristic_lookup_table[index];
775 }
else if (obstacle_heuristic <= 0.0) {
778 static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
779 to[0] = goal_coords.x;
780 to[1] = goal_coords.y;
781 to[2] = goal_coords.theta * motion_table.num_angle_quantization;
782 from[0] = node_coords.x;
783 from[1] = node_coords.y;
784 from[2] = node_coords.theta * motion_table.num_angle_quantization;
785 motion_heuristic = motion_table.state_space->distance(from(), to());
788 return motion_heuristic;
792 const float & lookup_table_dim,
793 const MotionModel & motion_model,
794 const unsigned int & dim_3_size,
798 if (motion_model == MotionModel::DUBIN) {
799 motion_table.state_space = std::make_shared<ompl::base::DubinsStateSpace>(
800 search_info.minimum_turning_radius);
801 }
else if (motion_model == MotionModel::REEDS_SHEPP) {
802 motion_table.state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
803 search_info.minimum_turning_radius);
805 throw std::runtime_error(
806 "Node attempted to precompute distance heuristics "
807 "with invalid motion model!");
810 ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
814 size_lookup = lookup_table_dim;
815 float motion_heuristic = 0.0;
816 unsigned int index = 0;
817 int dim_3_size_int =
static_cast<int>(dim_3_size);
818 float angular_bin_size = 2 * M_PI /
static_cast<float>(dim_3_size);
825 dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
826 for (
float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
827 for (
float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
828 for (
int heading = 0; heading != dim_3_size_int; heading++) {
831 from[2] = heading * angular_bin_size;
832 motion_heuristic = motion_table.state_space->distance(from(), to());
833 dist_heuristic_lookup_table[index] = motion_heuristic;
841 std::function<
bool(
const uint64_t &,
844 const bool & traverse_unknown,
845 NodeVector & neighbors)
850 const MotionPoses motion_projections = motion_table.
getProjections(
this);
852 for (
unsigned int i = 0; i != motion_projections.size(); i++) {
854 static_cast<unsigned int>(motion_projections[i]._x),
855 static_cast<unsigned int>(motion_projections[i]._y),
856 static_cast<unsigned int>(motion_projections[i]._theta),
857 motion_table.size_x, motion_table.num_angle_quantization);
859 if (NeighborGetter(index, neighbor) && !neighbor->
wasVisited()) {
862 initial_node_coords = neighbor->pose;
865 motion_projections[i]._x,
866 motion_projections[i]._y,
867 motion_projections[i]._theta));
868 if (neighbor->
isNodeValid(traverse_unknown, collision_checker)) {
870 neighbors.push_back(neighbor);
872 neighbor->
setPose(initial_node_coords);
886 while (current_node->parent) {
887 path.push_back(current_node->pose);
889 path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta);
890 current_node = current_node->parent;
894 path.push_back(current_node->pose);
896 path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta);
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.
float getCost()
Get cost at footprint pose in costmap.
NodeHybrid implementation for graph, Hybrid-A*.
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.
uint64_t getIndex()
Gets cell index.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker)
Check if this node is valid.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
~NodeHybrid()
A destructor for nav2_smac_planner::NodeHybrid.
void getNeighbors(std::function< bool(const uint64_t &, nav2_smac_planner::NodeHybrid *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
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.
void reset()
Reset method for new search.
void setMotionPrimitiveIndex(const unsigned int &idx, const TurnDirection &turn_dir)
Sets the motion primitive index used to achieve node in search.
unsigned int & getMotionPrimitiveIndex()
Gets the motion primitive index used to achieve node in search.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &cost_penalty)
Compute the Obstacle heuristic.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
bool wasVisited()
Gets if cell has been visited in search.
static float getHeuristicCost(const Coordinates &node_coords, const CoordinateVector &goals_coords)
Get cost of heuristic of node.
TurnDirection & getTurnDirection()
Gets the motion primitive turning direction used to achieve node in search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
static void resetObstacleHeuristic(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, const unsigned int &start_x, const unsigned int &start_y, const unsigned int &goal_x, const unsigned int &goal_y)
reset the obstacle heuristic state
void initReedsShepp(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Reeds-Shepp model.
MotionPoses getProjections(const NodeHybrid *node)
Get projections of motion models.
void initDubin(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Dubin model.
A struct for poses in motion primitives.
NodeHybrid implementation of coordinate structure.
Search properties and penalties.