diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 6ea7709bfe..84152d21c3 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -170,13 +170,11 @@ void SmacPlannerHybrid::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT")); node->get_parameter(name + ".goal_heading_mode", goal_heading_type); - GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type); - if (goal_heading_mode == GoalHeadingMode::UNKNOWN) { + _goal_heading_mode = fromStringToGH(goal_heading_type); + if (_goal_heading_mode == GoalHeadingMode::UNKNOWN) { std::string error_msg = "Unable to get GoalHeader type. Given '" + goal_heading_type + "' " "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. "; throw nav2_core::PlannerException(error_msg); - } else { - _goal_heading_mode = goal_heading_mode; } _motion_model = fromString(_motion_model_for_search); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 0c36a0184c..ddc5a5c90b 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -145,14 +145,11 @@ void SmacPlannerLattice::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT")); node->get_parameter(name + ".goal_heading_mode", goal_heading_type); - GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type); - goal_heading_mode = fromStringToGH(goal_heading_type); - if (goal_heading_mode == GoalHeadingMode::UNKNOWN) { + _goal_heading_mode = fromStringToGH(goal_heading_type); + if (_goal_heading_mode == GoalHeadingMode::UNKNOWN) { std::string error_msg = "Unable to get GoalHeader type. Given '" + goal_heading_type + "' " "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. "; throw nav2_core::PlannerException(error_msg); - } else { - _goal_heading_mode = goal_heading_mode; } _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath);