From e99f5d7f73282bfa842e22da76d545e2015c0880 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 15 May 2023 17:38:56 +0900 Subject: [PATCH] fix(intersection): fixed bad optional access (#3712) (#477) Signed-off-by: Mamoru Sobue --- .../src/scene_module/intersection/scene_intersection.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp index d005243566ee7..96a307c6195b3 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp @@ -324,7 +324,10 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_line_idx = occlusion_first_stop_line_idx; // insert creep velocity [default_stop_line, occlusion_stop_line) insert_creep_during_occlusion = - std::make_pair(default_stop_line_idx_opt.value(), occlusion_peeking_line_idx_opt.value()); + default_stop_line_idx_opt && occlusion_peeking_line_idx_opt + ? std::make_optional>( + default_stop_line_idx_opt.value(), occlusion_peeking_line_idx_opt.value()) + : std::nullopt; occlusion_state_ = OcclusionState::BEFORE_FIRST_STOP_LINE; } } else if (occlusion_state_ != OcclusionState::CLEARED) {