Skip to content

Commit 0a881f3

Browse files
feat(start_planner):speed up start planner v0.36 (#1639)
feat(start_planner, lane_departure_checker): speed up by updating polygons (autowarefoundation#9309) speed up by updating polygons Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 7b2e1b6 commit 0a881f3

File tree

3 files changed

+17
-5
lines changed

3 files changed

+17
-5
lines changed

control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,8 @@ class LaneDepartureChecker
147147

148148
PathWithLaneId cropPointsOutsideOfLanes(
149149
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path,
150-
const size_t end_index);
150+
const size_t end_index, std::vector<lanelet::Id> & fused_lanelets_id,
151+
std::optional<autoware::universe_utils::Polygon2d> & fused_lanelets_polygon);
151152

152153
static bool isOutOfLane(
153154
const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint);

control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

+11-3
Original file line numberDiff line numberDiff line change
@@ -340,13 +340,21 @@ bool LaneDepartureChecker::checkPathWillLeaveLane(
340340
}
341341

342342
PathWithLaneId LaneDepartureChecker::cropPointsOutsideOfLanes(
343-
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index)
343+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index,
344+
std::vector<lanelet::Id> & fused_lanelets_id,
345+
std::optional<autoware::universe_utils::Polygon2d> & fused_lanelets_polygon)
344346
{
345347
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
346348

347349
PathWithLaneId temp_path;
348-
const auto fused_lanelets_polygon = getFusedLaneletPolygonForPath(lanelet_map_ptr, path);
349-
if (path.points.empty() || !fused_lanelets_polygon) return temp_path;
350+
351+
// Update the lanelet polygon for the current path
352+
if (
353+
path.points.empty() || !updateFusedLaneletPolygonForPath(
354+
lanelet_map_ptr, path, fused_lanelets_id, fused_lanelets_polygon)) {
355+
return temp_path;
356+
}
357+
350358
const auto vehicle_footprints =
351359
utils::createVehicleFootprints(path, *vehicle_info_ptr_, param_.footprint_extra_margin);
352360

planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,8 @@ std::optional<PullOutPath> ShiftPullOut::plan(
6666
std::vector<lanelet::Id> fused_id_start_to_end{};
6767
std::optional<autoware::universe_utils::Polygon2d> fused_polygon_start_to_end = std::nullopt;
6868

69+
std::vector<lanelet::Id> fused_id_crop_points{};
70+
std::optional<autoware::universe_utils::Polygon2d> fused_polygon_crop_points = std::nullopt;
6971
// get safe path
7072
for (auto & pull_out_path : pull_out_paths) {
7173
universe_utils::ScopedTimeTrack st("get safe path", *time_keeper_);
@@ -120,7 +122,8 @@ std::optional<PullOutPath> ShiftPullOut::plan(
120122
common_parameters.ego_nearest_yaw_threshold);
121123

122124
const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes(
123-
lanelet_map_ptr, shift_path, start_segment_idx);
125+
lanelet_map_ptr, shift_path, start_segment_idx, fused_id_crop_points,
126+
fused_polygon_crop_points);
124127
if (cropped_path.points.empty()) {
125128
planner_debug_data.conditions_evaluation.emplace_back("cropped path is empty");
126129
continue;

0 commit comments

Comments
 (0)