From 4e0b4ac964adeb44ea7f8e8a92ff99ffbadeb275 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 26 Jan 2024 16:03:48 +0900 Subject: [PATCH] fix(start_planner): update drivable area info and enable idle to running state transition (#6172) Update drivable area info and enable idle to running state transition Signed-off-by: kyoichi-sugahara --- .../utils/drivable_area_expansion/static_drivable_area.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 03fae6864fe50..4e25e9257ddfd 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1884,6 +1884,10 @@ DrivableAreaInfo combineDrivableAreaInfo( drivable_area_info1.enable_expanding_intersection_areas || drivable_area_info2.enable_expanding_intersection_areas; + // drivable margin + combined_drivable_area_info.drivable_margin = + std::max(drivable_area_info1.drivable_margin, drivable_area_info2.drivable_margin); + return combined_drivable_area_info; }