Skip to content

Commit

Permalink
remove unnecessary local variable
Browse files Browse the repository at this point in the history
Signed-off-by: stevedan <[email protected]>
  • Loading branch information
stevedanomodolor committed Nov 18, 2024
1 parent 66537c8 commit e06f1db
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 9 deletions.
6 changes: 2 additions & 4 deletions nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
7 changes: 2 additions & 5 deletions nav2_smac_planner/src/smac_planner_lattice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit e06f1db

Please sign in to comment.