From d2d5d58fd04860a81f0a9570d5996f9ae308dafb Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi Date: Mon, 9 Dec 2024 19:45:09 +0900 Subject: [PATCH] return non reversed lanes Signed-off-by: Zulfaqar Azmi --- .../src/utils/utils.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index e184731c4ff67..a8c4cda9c0327 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -1282,7 +1282,9 @@ std::vector get_preceding_lanes(const CommonDataPtr & co continue; } - lanelet::ConstLanelets non_overlapping_lanes(lanes_reversed.begin(), overlapped_itr); + // Lanes are not reversed by default. Avoid returning reversed lanes to prevent undefined + // behavior. + lanelet::ConstLanelets non_overlapping_lanes(overlapped_itr.base(), lanes.end()); non_overlapping_lanes_vec.push_back(non_overlapping_lanes); }