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