diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index 41944aa5b91..56bf8c74f16 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -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; @@ -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; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 5e659df14ef..2ffc213087f 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -419,7 +419,7 @@ 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; @@ -427,7 +427,7 @@ class NodeLattice // 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; diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index 4650514efdf..5c597c8c754 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -46,7 +46,7 @@ std::shared_ptr 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 @@ -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); @@ -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; @@ -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()); @@ -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 diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index b881cbf484c..90ef8301464 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -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 @@ -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 = @@ -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; @@ -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()); @@ -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