Skip to content

Commit

Permalink
improve naming
Browse files Browse the repository at this point in the history
  • Loading branch information
stevedanomodolor committed Mar 25, 2024
1 parent 362a845 commit 88fe2dc
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 16 deletions.
4 changes: 2 additions & 2 deletions nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -463,7 +463,7 @@ class NodeHybrid
* \brief Sets the goal mode for the current search
* \param goal_heading_mode The goal heading mode to use
*/
static void setGoalHeadingMode(const GoalHeadingMode & goal_heading_mode);
static void setGoalHeadingMode(const GoalHeadingMode & current_goal_heading_mode);

NodeHybrid * parent;
Coordinates pose;
Expand All @@ -482,7 +482,7 @@ class NodeHybrid
// Dubin / Reeds-Shepp lookup and size for dereferencing
static LookupTable dist_heuristic_lookup_table;
static float size_lookup;
static GoalHeadingMode current_goal_heading_mode;
static GoalHeadingMode goal_heading_mode;

private:
float _cell_cost;
Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,15 +419,15 @@ class NodeLattice
* \brief Sets the goal mode for the current search
* \param goal_heading_mode The goal heading mode to use
*/
static void setGoalHeadingMode(const GoalHeadingMode & goal_heading_mode);
static void setGoalHeadingMode(const GoalHeadingMode & current_goal_heading_mode);

NodeLattice * parent;
Coordinates pose;
static LatticeMotionTable motion_table;
// Dubin / Reeds-Shepp lookup and size for dereferencing
static LookupTable dist_heuristic_lookup_table;
static float size_lookup;
static GoalHeadingMode current_goal_heading_mode;
static GoalHeadingMode goal_heading_mode;

private:
float _cell_cost;
Expand Down
12 changes: 6 additions & 6 deletions nav2_smac_planner/src/node_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ std::shared_ptr<nav2_costmap_2d::InflationLayer> NodeHybrid::inflation_layer = n

CostmapDownsampler NodeHybrid::downsampler;
ObstacleHeuristicQueue NodeHybrid::obstacle_heuristic_queue;
GoalHeadingMode NodeHybrid::current_goal_heading_mode;
GoalHeadingMode NodeHybrid::goal_heading_mode;

// Each of these tables are the projected motion models through
// time and space applied to the search on the current node in
Expand Down Expand Up @@ -441,7 +441,7 @@ float NodeHybrid::getHeuristicCost(
{
const float obstacle_heuristic =
getObstacleHeuristic(node_coords, goal_coords, motion_table.cost_penalty);
if (current_goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
if (goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
return obstacle_heuristic;
}
const float dist_heuristic = getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic);
Expand Down Expand Up @@ -784,7 +784,7 @@ void NodeHybrid::precomputeDistanceHeuristic(
const unsigned int & dim_3_size,
const SearchInfo & search_info)
{
if (current_goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
if (goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
// For all direction goal heading, we only consider the obstacle heuristic
// it does not make sense to precompute the distance heuristic to save computation
return;
Expand Down Expand Up @@ -826,7 +826,7 @@ void NodeHybrid::precomputeDistanceHeuristic(
from[2] = heading * angular_bin_size;
motion_heuristic = motion_table.state_space->distance(from(), to());
// we need to check for bidirectional goal heading and take the minimum
if (current_goal_heading_mode == GoalHeadingMode::BIDIRECTIONAL) {
if (goal_heading_mode == GoalHeadingMode::BIDIRECTIONAL) {
unsigned int heading_180_offset = (heading + (dim_3_size_int / 2)) % dim_3_size_int;
from[2] = heading_180_offset * angular_bin_size;
float motion_heuristic_180 = motion_table.state_space->distance(from(), to());
Expand Down Expand Up @@ -899,8 +899,8 @@ bool NodeHybrid::backtracePath(CoordinateVector & path)
return true;
}

void NodeHybrid::setGoalHeadingMode(const GoalHeadingMode & goal_heading_mode)
void NodeHybrid::setGoalHeadingMode(const GoalHeadingMode & current_goal_heading_mode)
{
current_goal_heading_mode = goal_heading_mode;
goal_heading_mode = current_goal_heading_mode;
}
} // namespace nav2_smac_planner
12 changes: 6 additions & 6 deletions nav2_smac_planner/src/node_lattice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace nav2_smac_planner
LatticeMotionTable NodeLattice::motion_table;
float NodeLattice::size_lookup = 25;
LookupTable NodeLattice::dist_heuristic_lookup_table;
GoalHeadingMode NodeLattice::current_goal_heading_mode;
GoalHeadingMode NodeLattice::goal_heading_mode;

// Each of these tables are the projected motion models through
// time and space applied to the search on the current node in
Expand Down Expand Up @@ -333,7 +333,7 @@ float NodeLattice::getHeuristicCost(
// get obstacle heuristic value
const float obstacle_heuristic = getObstacleHeuristic(
node_coords, goal_coords, motion_table.cost_penalty);
if (current_goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
if (goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
return obstacle_heuristic;
}
const float distance_heuristic =
Expand Down Expand Up @@ -430,7 +430,7 @@ void NodeLattice::precomputeDistanceHeuristic(
const unsigned int & dim_3_size,
const SearchInfo & search_info)
{
if (current_goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
if (goal_heading_mode == GoalHeadingMode::ALL_DIRECTION) {
// For all direction goal heading, we only consider the obstacle heuristic
// it does not make sense to precompute the distance heuristic to save computation
return;
Expand Down Expand Up @@ -471,7 +471,7 @@ void NodeLattice::precomputeDistanceHeuristic(
from[2] = motion_table.getAngleFromBin(heading);
motion_heuristic = motion_table.state_space->distance(from(), to());
// we need to check for bidirectional goal heading and take the minimum
if (current_goal_heading_mode == GoalHeadingMode::BIDIRECTIONAL) {
if (goal_heading_mode == GoalHeadingMode::BIDIRECTIONAL) {
unsigned int heading_180_offset = (heading + (dim_3_size_int / 2)) % dim_3_size_int;
from[2] = motion_table.getAngleFromBin(heading_180_offset);
float motion_heuristic_180 = motion_table.state_space->distance(from(), to());
Expand Down Expand Up @@ -609,9 +609,9 @@ void NodeLattice::addNodeToPath(
}
}

void NodeLattice::setGoalHeadingMode(const GoalHeadingMode & goal_heading_mode)
void NodeLattice::setGoalHeadingMode(const GoalHeadingMode & current_goal_heading_mode)
{
current_goal_heading_mode = goal_heading_mode;
goal_heading_mode = current_goal_heading_mode;
}

} // namespace nav2_smac_planner

0 comments on commit 88fe2dc

Please sign in to comment.