diff --git a/common/autoware_lanelet2_utils/src/geometry.cpp b/common/autoware_lanelet2_utils/src/geometry.cpp index a83ebc6b38..dd9ae91ca1 100644 --- a/common/autoware_lanelet2_utils/src/geometry.cpp +++ b/common/autoware_lanelet2_utils/src/geometry.cpp @@ -500,11 +500,15 @@ std::optional combine_lanelets_shape(const lanelet::Const } const auto combined_lanelet_opt = create_safe_lanelet(lefts, rights); - assert(combined_lanelet_opt.has_value() && "lefts or rights bound size is less than 2."); + if (!combined_lanelet_opt.has_value()) { + return std::nullopt; + } auto combined_lanelet = remove_const(*combined_lanelet_opt); const auto center_line_opt = create_safe_linestring(centers); - assert(center_line_opt.has_value() && "centers size is less than 2."); + if (!center_line_opt.has_value()) { + return std::nullopt; + } const auto center_line = remove_const(*center_line_opt); combined_lanelet.setCenterline(center_line);