diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 9df0791ed9375..eb3385d17545f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1369,7 +1369,7 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() path.points, status_.pull_out_path.start_pose.position); const auto shift_end_idx = autoware::motion_utils::findNearestIndex(path.points, status_.pull_out_path.end_pose.position); - const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes(planner_data_); const auto is_ignore_signal = [this](const lanelet::Id & id) { if (!ignore_signal_.has_value()) {