diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 3b272fd8c6722..db327e89a59a5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -662,20 +662,15 @@ std::optional getOverlappedLaneletId(const std::vector & return {}; } - size_t overlapped_idx = lanes.size(); for (size_t i = 0; i < lanes.size() - 2; ++i) { for (size_t j = i + 2; j < lanes.size(); ++j) { if (overlaps(lanes.at(i), lanes.at(j))) { - overlapped_idx = std::min(overlapped_idx, j); + return j; } } } - if (overlapped_idx == lanes.size()) { - return {}; - } - - return overlapped_idx; + return {}; } std::vector cutOverlappedLanes(