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 18627e8396239..abad804503476 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 @@ -1347,7 +1347,7 @@ std::pair, bool> getBoundWithFreeSpaceAreas( if (intersect.has_value()) { ret.emplace_back( - lanelet::InvalId, intersect.value().x, intersect.value().y, intersect.value().z); + lanelet::InvalId, intersect.value().x, intersect.value().y, toGeomMsgPt(bound.at(i)).z); break; } }