@@ -258,17 +258,39 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
258
258
road_lane_reference_path_to_shift_end.points .back ().point .pose );
259
259
pull_over_path.debug_poses .push_back (prev_module_path_terminal_pose);
260
260
261
- // check if the parking path will leave lanes
262
- const auto drivable_lanes =
263
- utils::generateDrivableLanesWithShoulderLanes (road_lanes, shoulder_lanes);
264
- const auto & dp = planner_data_->drivable_area_expansion_parameters ;
265
- const auto expanded_lanes = utils::expandLanelets (
266
- drivable_lanes, dp.drivable_area_left_bound_offset , dp.drivable_area_right_bound_offset ,
267
- dp.drivable_area_types_to_skip );
268
- const auto combined_drivable = utils::combineDrivableLanes (
269
- expanded_lanes, previous_module_output_.drivable_area_info .drivable_lanes );
270
- if (lane_departure_checker_.checkPathWillLeaveLane (
271
- utils::transformToLanelets (combined_drivable), pull_over_path.getParkingPath ())) {
261
+ // check if the parking path will leave drivable area and lanes
262
+ const bool is_in_parking_lots = std::invoke ([&]() -> bool {
263
+ const auto & p = planner_data_->parameters ;
264
+ const auto parking_lot_polygons =
265
+ lanelet::utils::query::getAllParkingLots (planner_data_->route_handler ->getLaneletMapPtr ());
266
+ const auto path_footprints = goal_planner_utils::createPathFootPrints (
267
+ pull_over_path.getParkingPath (), p.base_link2front , p.base_link2rear , p.vehicle_width );
268
+ const auto is_footprint_in_any_polygon = [&parking_lot_polygons](const auto & footprint) {
269
+ return std::any_of (
270
+ parking_lot_polygons.begin (), parking_lot_polygons.end (),
271
+ [&footprint](const auto & polygon) {
272
+ return lanelet::geometry::within (footprint, lanelet::utils::to2D (polygon).basicPolygon ());
273
+ });
274
+ };
275
+ return std::all_of (
276
+ path_footprints.begin (), path_footprints.end (),
277
+ [&is_footprint_in_any_polygon](const auto & footprint) {
278
+ return is_footprint_in_any_polygon (footprint);
279
+ });
280
+ });
281
+ const bool is_in_lanes = std::invoke ([&]() -> bool {
282
+ const auto drivable_lanes =
283
+ utils::generateDrivableLanesWithShoulderLanes (road_lanes, shoulder_lanes);
284
+ const auto & dp = planner_data_->drivable_area_expansion_parameters ;
285
+ const auto expanded_lanes = utils::expandLanelets (
286
+ drivable_lanes, dp.drivable_area_left_bound_offset , dp.drivable_area_right_bound_offset ,
287
+ dp.drivable_area_types_to_skip );
288
+ const auto combined_drivable = utils::combineDrivableLanes (
289
+ expanded_lanes, previous_module_output_.drivable_area_info .drivable_lanes );
290
+ return !lane_departure_checker_.checkPathWillLeaveLane (
291
+ utils::transformToLanelets (combined_drivable), pull_over_path.getParkingPath ());
292
+ });
293
+ if (!is_in_parking_lots && !is_in_lanes) {
272
294
return {};
273
295
}
274
296
0 commit comments