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

fix(behavior_path_planner): fix drivable area expansion method outside intersection #2861

Merged
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 @@ -2573,12 +2573,8 @@ void AvoidanceModule::generateExtendedDrivableArea(PathWithLaneId & path) const

// 2. when there are multiple turning lanes whose previous lanelet is the same in
// intersection
const lanelet::ConstLanelets next_lanes_from_intersection = std::invoke(
const lanelet::ConstLanelets next_lanes = std::invoke(
[&route_handler](const lanelet::ConstLanelet & lane) {
if (!lane.hasAttribute("turn_direction")) {
return lanelet::ConstLanelets{};
}

// get previous lane, and return false if previous lane does not exist
lanelet::ConstLanelets prev_lanes;
if (!route_handler->getPreviousLaneletsWithinRoute(lane, &prev_lanes)) {
Expand All @@ -2598,7 +2594,7 @@ void AvoidanceModule::generateExtendedDrivableArea(PathWithLaneId & path) const

// 2.1 look for neighbour lane, where end line of the lane is connected to end line of the
// original lane
for (const auto & next_lane : next_lanes_from_intersection) {
for (const auto & next_lane : next_lanes) {
if (current_lane.id() == next_lane.id()) {
continue;
}
Expand Down