From c4c594e91f1b1e9dcc72d881d387ec6b6d8b133d Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Tue, 6 Aug 2024 19:11:02 +0900 Subject: [PATCH] set current_lanes to avoid accessing empty current_lanes Signed-off-by: Kento Yabuuchi --- .../autoware_behavior_path_lane_change_module/src/scene.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 3fc64736731f5..75efc65c2997c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -85,6 +85,7 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); if (target_lanes.empty()) { + safe_path.info.current_lanes = current_lanes; return {false, false}; }