Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(start_planner): speed up start planner v0.36 #1639

Merged
merged 1 commit into from
Nov 13, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,8 @@ class LaneDepartureChecker

PathWithLaneId cropPointsOutsideOfLanes(
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path,
const size_t end_index);
const size_t end_index, std::vector<lanelet::Id> & fused_lanelets_id,
std::optional<autoware::universe_utils::Polygon2d> & fused_lanelets_polygon);

static bool isOutOfLane(
const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -340,13 +340,21 @@ bool LaneDepartureChecker::checkPathWillLeaveLane(
}

PathWithLaneId LaneDepartureChecker::cropPointsOutsideOfLanes(
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index)
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index,
std::vector<lanelet::Id> & fused_lanelets_id,
std::optional<autoware::universe_utils::Polygon2d> & fused_lanelets_polygon)
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

PathWithLaneId temp_path;
const auto fused_lanelets_polygon = getFusedLaneletPolygonForPath(lanelet_map_ptr, path);
if (path.points.empty() || !fused_lanelets_polygon) return temp_path;

// Update the lanelet polygon for the current path
if (
path.points.empty() || !updateFusedLaneletPolygonForPath(
lanelet_map_ptr, path, fused_lanelets_id, fused_lanelets_polygon)) {
return temp_path;
}

const auto vehicle_footprints =
utils::createVehicleFootprints(path, *vehicle_info_ptr_, param_.footprint_extra_margin);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ std::optional<PullOutPath> ShiftPullOut::plan(
std::vector<lanelet::Id> fused_id_start_to_end{};
std::optional<autoware::universe_utils::Polygon2d> fused_polygon_start_to_end = std::nullopt;

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

const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes(
lanelet_map_ptr, shift_path, start_segment_idx);
lanelet_map_ptr, shift_path, start_segment_idx, fused_id_crop_points,
fused_polygon_crop_points);
if (cropped_path.points.empty()) {
planner_debug_data.conditions_evaluation.emplace_back("cropped path is empty");
continue;
Expand Down
Loading