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 1951bdbfe73d7..b5c7ddff301bc 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 @@ -619,6 +619,14 @@ std::vector updateBoundary( 0 < front_offset ? start_poly.bound_seg_idx + 1 : start_poly.bound_seg_idx; const size_t removed_end_idx = end_poly.bound_seg_idx; + if (removed_start_idx > removed_end_idx || removed_end_idx >= updated_bound.size()) { + auto clock{rclcpp::Clock{RCL_ROS_TIME}}; + RCLCPP_ERROR_STREAM_THROTTLE( + rclcpp::get_logger("behavior_path_planner").get_child("utils"), clock, 1000, + "Invalid index for erase in updateBoundary. Skipping."); + continue; + } + updated_bound.erase( updated_bound.begin() + removed_start_idx, updated_bound.begin() + removed_end_idx + 1);