diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 3223ff4913a..4bbe5c55ca7 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -3,7 +3,6 @@ project(nav2_smac_planner) set(CMAKE_BUILD_TYPE Release) #Debug, Release - find_package(ament_cmake REQUIRED) find_package(nav2_common REQUIRED) find_package(rclcpp REQUIRED) diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp index ab32d4c63cf..63a5098386f 100644 --- a/nav2_smac_planner/src/analytic_expansion.cpp +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -63,7 +63,7 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalytic float current_best_score = std::numeric_limits::max(); AnalyticExpansionNodes current_best_analytic_nodes = {}; - NodePtr current_best_goal_node = nullptr; + unsigned int current_best_goal_index = 0; NodePtr current_best_node = nullptr; for (unsigned int i = 0; i < goals_node.size(); i++) { closest_distance = std::min( @@ -159,7 +159,7 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalytic { current_best_score = best_score; current_best_node = node; - current_best_goal_node = goals_node[i]; + current_best_goal_index = i; current_best_analytic_nodes = analytic_nodes; } @@ -168,7 +168,7 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalytic } if(!current_best_analytic_nodes.empty()) { - return setAnalyticPath(current_best_node, current_best_goal_node, current_best_analytic_nodes); + return setAnalyticPath(current_best_node, goals_node[current_best_goal_index], current_best_analytic_nodes); } analytic_iterations--; } diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 6fe8118f2f5..c565ba46afd 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -177,7 +177,10 @@ void SmacPlannerHybrid::configure( "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. "; throw nav2_core::PlannerException(error_msg); } - _goal_heading_mode = goal_heading_mode; + else + { + _goal_heading_mode = goal_heading_mode; + } _motion_model = fromString(_motion_model_for_search); if (_motion_model == MotionModel::UNKNOWN) { @@ -650,7 +653,10 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector para "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ", goal_heading_type.c_str()); } - _goal_heading_mode = goal_heading_mode; + else + { + _goal_heading_mode = goal_heading_mode; + } } } } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 7f59ae3a757..df71cc41ce4 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -153,7 +153,10 @@ void SmacPlannerLattice::configure( "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. "; throw nav2_core::PlannerException(error_msg); } - _goal_heading_mode = goal_heading_mode; + else + { + _goal_heading_mode = goal_heading_mode; + } _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath); _search_info.minimum_turning_radius = @@ -560,7 +563,10 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ", goal_heading_type.c_str()); } - _goal_heading_mode = goal_heading_mode; + else + { + _goal_heading_mode = goal_heading_mode; + } } } }