From 3dbcae24e71a5496d83fa1bff7d1ae5682c714c1 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 8 Aug 2022 18:30:09 +0900 Subject: [PATCH] fix(behavior_path_planner): fix turn singal (#1539) * fix(behavior_path_planner): fix turn singal Signed-off-by: tomoya.kimura * apply pre-commit Signed-off-by: tomoya.kimura --- planning/behavior_path_planner/src/turn_signal_decider.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 0c32fed8d5d87..f42cdac7ee436 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -71,6 +71,9 @@ std::pair TurnSignalDecider::getIntersectionTurnS const double distance_from_vehicle_front = accumulated_distance - vehicle_pose_frenet.length - base_link2front_; if (distance_from_vehicle_front > intersection_search_distance_) { + if (turn_signal.command == TurnIndicatorsCommand::DISABLE) { + distance = std::numeric_limits::max(); + } return std::make_pair(turn_signal, distance); } // TODO(Horibe): Route Handler should be a library. @@ -103,7 +106,7 @@ std::pair TurnSignalDecider::getIntersectionTurnS } } } - if (turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) { + if (turn_signal.command == TurnIndicatorsCommand::DISABLE) { distance = std::numeric_limits::max(); } return std::make_pair(turn_signal, distance);