Skip to content

Commit

Permalink
refactor(start_planner): calculate drivable lanes efficiently (#6105)
Browse files Browse the repository at this point in the history
* Refactor ShiftPullOut class and update expanded drivable lanes

Signed-off-by: kyoichi-sugahara <[email protected]>

* Refactor drivable lane functions

Signed-off-by: kyoichi-sugahara <[email protected]>

* Fix lane departure check in ShiftPullOut::plan()

Signed-off-by: kyoichi-sugahara <[email protected]>

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Jan 20, 2024
1 parent 94357d2 commit bbf678d
Show file tree
Hide file tree
Showing 4 changed files with 49 additions and 21 deletions.
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 @@ -49,11 +49,6 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos

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);
Expand All @@ -80,20 +75,6 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
shift_path.points.begin() + pull_out_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
Expand All @@ -107,7 +88,7 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
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));
Expand All @@ -121,7 +102,7 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
// check lane departure
if (
parameters_.check_shift_path_lane_departure &&
lane_departure_checker_->checkPathWillLeaveLane(expanded_lanes, path_shift_start_to_end)) {
lane_departure_checker_->checkPathWillLeaveLane(drivable_lanes_, path_shift_start_to_end)) {
continue;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ void StartPlannerModule::initVariables()
debug_marker_.markers.clear();
initializeSafetyCheckParameters();
initializeCollisionCheckDebugMap(debug_data_.collision_check);
updateDrivableLanes();
}

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

void StartPlannerModule::incrementPathIndex()
Expand Down Expand Up @@ -1325,6 +1327,42 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
}
}

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

0 comments on commit bbf678d

Please sign in to comment.