diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 7b1fa47823e64..0c32fed8d5d87 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -98,14 +98,14 @@ std::pair TurnSignalDecider::getIntersectionTurnS turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; } else if (lane_attribute == std::string("right")) { turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } else { - // when lane_attribute is straight, return the turn signal with max distance - return std::make_pair(turn_signal, std::numeric_limits::max()); } distance = distance_from_vehicle_front; } } } + if (turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) { + distance = std::numeric_limits::max(); + } return std::make_pair(turn_signal, distance); } } // namespace behavior_path_planner