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

refactor(start_planner): calculate drivable lanes efficiently #6105

Merged
Show file tree
Hide file tree
Changes from 6 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 @@ -50,6 +50,11 @@ class ShiftPullOut : public PullOutPlannerBase
ShiftedPath & shifted_path, const Pose & start_pose, const Pose & end_pose,
const double longitudinal_acc, const double lateral_acc);

void setDrivableLanes(const lanelet::ConstLanelets & drivable_lanes)
{
drivable_lanes_ = drivable_lanes;
}

std::shared_ptr<LaneDepartureChecker> lane_departure_checker_;

private:
Expand All @@ -58,6 +63,8 @@ class ShiftPullOut : public PullOutPlannerBase
double calcPullOutLongitudinalDistance(
const double lon_acc, const double shift_time, const double shift_length,
const double max_curvature, const double min_distance) const;

lanelet::ConstLanelets drivable_lanes_;
};
} // namespace behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,8 @@ class StartPlannerModule : public SceneModuleInterface
const std::vector<PoseWithVelocityStamped> & ego_predicted_path) const;
bool isSafePath() const;
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;
void updateDrivableLanes();
lanelet::ConstLanelets createDrivableLanes() const;

// check if the goal is located behind the ego in the same route segment.
bool isGoalBehindOfEgoInSameRouteSegment() const;
Expand Down
23 changes: 2 additions & 21 deletions planning/behavior_path_start_planner_module/src/shift_pull_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,90 +48,71 @@
const auto & common_parameters = planner_data_->parameters;

const double backward_path_length =
planner_data_->parameters.backward_path_length + parameters_.max_back_distance;
const auto pull_out_lanes = getPullOutLanes(planner_data_, backward_path_length);
if (pull_out_lanes.empty()) {
return std::nullopt;
}

const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
/*forward_only_in_route*/ true);
// find candidate paths
auto pull_out_paths = calcPullOutPaths(*route_handler, road_lanes, start_pose, goal_pose);
if (pull_out_paths.empty()) {
return std::nullopt;
}

// get safe path
for (auto & pull_out_path : pull_out_paths) {
auto & shift_path =
pull_out_path.partial_paths.front(); // shift path is not separate but only one.

// check lane_departure with path between pull_out_start to pull_out_end
PathWithLaneId path_start_to_end{};
{
const size_t pull_out_start_idx = findNearestIndex(shift_path.points, start_pose.position);

// calculate collision check end idx
const size_t collision_check_end_idx = std::invoke([&]() {
const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose(
shift_path.points, pull_out_path.end_pose.position,
parameters_.collision_check_distance_from_end);

if (collision_check_end_pose) {
return findNearestIndex(shift_path.points, collision_check_end_pose->position);
} else {
return shift_path.points.size() - 1;
}
});
path_start_to_end.points.insert(
path_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx,
shift_path.points.begin() + collision_check_end_idx + 1);
}

// extract shoulder lanes from pull out lanes
lanelet::ConstLanelets shoulder_lanes;
std::copy_if(
pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes),
[&route_handler](const auto & pull_out_lane) {
return route_handler->isShoulderLanelet(pull_out_lane);
});
const auto drivable_lanes =
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
const auto & dp = planner_data_->drivable_area_expansion_parameters;
const auto expanded_lanes = utils::transformToLanelets(utils::expandLanelets(
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
dp.drivable_area_types_to_skip));

// crop backward path
// removes points which are out of lanes up to the start pose.
// this ensures that the backward_path stays within the drivable area when starting from a
// narrow place.
const size_t start_segment_idx = motion_utils::findFirstNearestIndexWithSoftConstraints(
shift_path.points, start_pose, common_parameters.ego_nearest_dist_threshold,
common_parameters.ego_nearest_yaw_threshold);
PathWithLaneId cropped_path{};
for (size_t i = 0; i < shift_path.points.size(); ++i) {
const Pose pose = shift_path.points.at(i).point.pose;
const auto transformed_vehicle_footprint =
transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(pose));
const bool is_out_of_lane =
LaneDepartureChecker::isOutOfLane(expanded_lanes, transformed_vehicle_footprint);
LaneDepartureChecker::isOutOfLane(drivable_lanes_, transformed_vehicle_footprint);
if (i <= start_segment_idx) {
if (!is_out_of_lane) {
cropped_path.points.push_back(shift_path.points.at(i));
}
} else {
cropped_path.points.push_back(shift_path.points.at(i));
}
}
shift_path.points = cropped_path.points;

// check lane departure
if (
parameters_.check_shift_path_lane_departure &&
lane_departure_checker_->checkPathWillLeaveLane(expanded_lanes, path_start_to_end)) {
lane_departure_checker_->checkPathWillLeaveLane(drivable_lanes_, path_start_to_end)) {

Check notice on line 115 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

ShiftPullOut::plan decreases in cyclomatic complexity from 11 to 10, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
continue;
}

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1165 to 1198, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -127,6 +127,7 @@
debug_marker_.markers.clear();
initializeSafetyCheckParameters();
initializeCollisionCheckDebugMap(start_planner_data_.collision_check);
updateDrivableLanes();
}

void StartPlannerModule::updateEgoPredictedPathParams(
Expand Down Expand Up @@ -559,6 +560,7 @@
void StartPlannerModule::resetStatus()
{
status_ = PullOutStatus{};
updateDrivableLanes();
}

void StartPlannerModule::incrementPathIndex()
Expand Down Expand Up @@ -1325,6 +1327,42 @@
}
}

void StartPlannerModule::updateDrivableLanes()
{
const auto drivable_lanes = createDrivableLanes();
for (auto & planner : start_planners_) {
auto shift_pull_out = std::dynamic_pointer_cast<ShiftPullOut>(planner);

if (shift_pull_out) {
shift_pull_out->setDrivableLanes(drivable_lanes);
}
}
}

lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
{
const double backward_path_length =
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
const auto pull_out_lanes =
start_planner_utils::getPullOutLanes(planner_data_, backward_path_length);
if (pull_out_lanes.empty()) {
return lanelet::ConstLanelets{};
}
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
/*forward_only_in_route*/ true);
// extract shoulder lanes from pull out lanes
lanelet::ConstLanelets shoulder_lanes;
std::copy_if(
pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes),
[this](const auto & pull_out_lane) {
return planner_data_->route_handler->isShoulderLanelet(pull_out_lane);
});
const auto drivable_lanes = utils::transformToLanelets(
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes));
return drivable_lanes;
}

void StartPlannerModule::setDebugData()
{
using marker_utils::addFootprintMarker;
Expand Down
Loading