Skip to content

Commit

Permalink
move analytic check outside loop
Browse files Browse the repository at this point in the history
  • Loading branch information
stevedanomodolor committed Mar 12, 2024
1 parent 8f22d39 commit fc0df4a
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 21 deletions.
2 changes: 1 addition & 1 deletion nav2_smac_planner/include/nav2_smac_planner/a_star.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,7 @@ class AStarAlgorithm
NodePtr _start;
NodeVector _goals;
NodeSet _goalsSet;
GoalHeadingMode _current_goal_heading_mode;
GoalHeadingMode _goal_heading_mode;

Graph _graph;
NodeQueue _queue;
Expand Down
8 changes: 4 additions & 4 deletions nav2_smac_planner/src/a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ void AStarAlgorithm<NodeT>::initialize(
_max_on_approach_iterations = max_on_approach_iterations;
_terminal_checking_interval = terminal_checking_interval;
_max_planning_time = max_planning_time;
_current_goal_heading_mode = goal_heading_mode;
NodeT::setGoalHeadingMode(_current_goal_heading_mode);
_goal_heading_mode = goal_heading_mode;
NodeT::setGoalHeadingMode(_goal_heading_mode);
NodeT::precomputeDistanceHeuristic(
lookup_table_size, _motion_model, dim_3_size, _search_info);
_dim3_size = dim_3_size;
Expand All @@ -96,7 +96,7 @@ void AStarAlgorithm<Node2D>::initialize(
_max_on_approach_iterations = max_on_approach_iterations;
_terminal_checking_interval = terminal_checking_interval;
_max_planning_time = max_planning_time;
_current_goal_heading_mode = goal_heading_mode;
_goal_heading_mode = goal_heading_mode;

if (dim_3_size != 1) {
throw std::runtime_error("Node type Node2D cannot be given non-1 dim 3 quantization.");
Expand Down Expand Up @@ -215,7 +215,7 @@ void AStarAlgorithm<NodeT>::setGoal(
CoordinateVector goals_coordinates;
unsigned int num_bins = NodeT::motion_table.num_angle_quantization;
unsigned int dim_3_half_bin = 0;
switch (_current_goal_heading_mode) {
switch (_goal_heading_mode) {
case GoalHeadingMode::DEFAULT:
_goals.push_back(addToGraph(NodeT::getIndex(mx, my, dim_3)));
goals_coordinates.push_back(
Expand Down
31 changes: 15 additions & 16 deletions nav2_smac_planner/src/analytic_expansion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,24 +65,23 @@ typename AnalyticExpansion<NodeT>::NodePtr AnalyticExpansion<NodeT>::tryAnalytic
AnalyticExpansionNodes current_best_analytic_nodes = {};
unsigned int current_best_goal_index = 0;
NodePtr current_best_node = nullptr;
for (unsigned int g = 0; g < goals_node.size(); g++) {
closest_distance = std::min(
closest_distance = std::min(
closest_distance,
static_cast<int>(NodeT::getHeuristicCost(node_coords, goals_node[0]->pose)));
// We want to expand at a rate of d/expansion_ratio,
// but check to see if we are so close that we would be expanding every iteration
// If so, limit it to the expansion ratio (rounded up)
int desired_iterations = std::max(
static_cast<int>(closest_distance / _search_info.analytic_expansion_ratio),
static_cast<int>(std::ceil(_search_info.analytic_expansion_ratio)));

// If we are closer now, we should update the target number of iterations to go
analytic_iterations =
std::min(analytic_iterations, desired_iterations);

// Always run the expansion on the first run in case there is a
// trivial path to be found
if (analytic_iterations <= 0) {
// We want to expand at a rate of d/expansion_ratio,
// but check to see if we are so close that we would be expanding every iteration
// If so, limit it to the expansion ratio (rounded up)
int desired_iterations = std::max(
static_cast<int>(closest_distance / _search_info.analytic_expansion_ratio),
static_cast<int>(std::ceil(_search_info.analytic_expansion_ratio)));
// If we are closer now, we should update the target number of iterations to go
analytic_iterations =
std::min(analytic_iterations, desired_iterations);

// Always run the expansion on the first run in case there is a
// trivial path to be found
if (analytic_iterations <= 0) {
for (unsigned int g = 0; g < goals_node.size(); g++) {
// Reset the counter and try the analytic path expansion
analytic_iterations = desired_iterations;
AnalyticExpansionNodes analytic_nodes =
Expand Down

0 comments on commit fc0df4a

Please sign in to comment.