Skip to content

Commit f3f853c

Browse files
authored
feat(goal_planner): allow shift pull over in parking lot outside lane (#7140)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 0e2f26d commit f3f853c

File tree

3 files changed

+52
-11
lines changed

3 files changed

+52
-11
lines changed

planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_
1717

1818
#include "behavior_path_goal_planner_module/goal_searcher_base.hpp"
19+
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
1920

2021
#include <lane_departure_checker/lane_departure_checker.hpp>
2122

@@ -41,6 +42,7 @@ using geometry_msgs::msg::Pose;
4142
using geometry_msgs::msg::Twist;
4243
using visualization_msgs::msg::Marker;
4344
using visualization_msgs::msg::MarkerArray;
45+
using Polygon2d = tier4_autoware_utils::Polygon2d;
4446

4547
lanelet::ConstLanelets getPullOverLanes(
4648
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
@@ -85,6 +87,10 @@ PathWithLaneId extendPath(
8587
const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path,
8688
const Pose & extend_pose);
8789

90+
std::vector<Polygon2d> createPathFootPrints(
91+
const PathWithLaneId & path, const double base_to_front, const double base_to_rear,
92+
const double width);
93+
8894
// debug
8995
MarkerArray createPullOverAreaMarkerArray(
9096
const tier4_autoware_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header,

planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp

+33-11
Original file line numberDiff line numberDiff line change
@@ -258,17 +258,39 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
258258
road_lane_reference_path_to_shift_end.points.back().point.pose);
259259
pull_over_path.debug_poses.push_back(prev_module_path_terminal_pose);
260260

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) {
272294
return {};
273295
}
274296

planning/behavior_path_goal_planner_module/src/util.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -433,4 +433,17 @@ PathWithLaneId extendPath(
433433
return extendPath(target_path, reference_path, extend_distance);
434434
}
435435

436+
std::vector<Polygon2d> createPathFootPrints(
437+
const PathWithLaneId & path, const double base_to_front, const double base_to_rear,
438+
const double width)
439+
{
440+
std::vector<Polygon2d> footprints;
441+
for (const auto & point : path.points) {
442+
const auto & pose = point.point.pose;
443+
footprints.push_back(
444+
tier4_autoware_utils::toFootprint(pose, base_to_front, base_to_rear, width));
445+
}
446+
return footprints;
447+
}
448+
436449
} // namespace behavior_path_planner::goal_planner_utils

0 commit comments

Comments
 (0)