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(lane_change): fix terminal stop distance (#5392) #984

Merged
merged 4 commits into from
Oct 31, 2023
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 @@ -363,10 +363,12 @@ lanelet::ConstLanelets getCurrentLanesFromPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data);

lanelet::ConstLanelets extendNextLane(
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes);
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes,
const bool only_in_route = false);

lanelet::ConstLanelets extendPrevLane(
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes);
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes,
const bool only_in_route = false);

lanelet::ConstLanelets extendLanes(
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes);
Expand Down
53 changes: 45 additions & 8 deletions planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2873,48 +2873,85 @@ lanelet::ConstLanelets getCurrentLanesFromPath(

lanelet::ConstLanelet current_lane;
lanelet::utils::query::getClosestLanelet(reference_lanes, current_pose, &current_lane);

return route_handler->getLaneletSequence(
auto current_lanes = route_handler->getLaneletSequence(
current_lane, current_pose, p.backward_path_length, p.forward_path_length);

// Extend the 'current_lanes' with previous lanes until it contains 'front_lane_ids'
// if the extended prior lanes is in same lane sequence with current lanes
const auto front_lane_ids = path.points.front().lane_ids;
auto have_front_lanes = [front_lane_ids](const auto & lanes) {
return std::any_of(lanes.begin(), lanes.end(), [&](const auto & lane) {
return std::find(front_lane_ids.begin(), front_lane_ids.end(), lane.id()) !=
front_lane_ids.end();
});
};
auto extended_lanes = current_lanes;
while (rclcpp::ok()) {
const size_t pre_extension_size = extended_lanes.size(); // Get existing size before extension
extended_lanes = extendPrevLane(route_handler, extended_lanes, true);
if (extended_lanes.size() == pre_extension_size) break;
if (have_front_lanes(extended_lanes)) {
current_lanes = extended_lanes;
break;
}
}

return current_lanes;
}

lanelet::ConstLanelets extendNextLane(
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes)
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes,
const bool only_in_route)
{
if (lanes.empty()) return lanes;

auto extended_lanes = lanes;

// Add next lane
const auto next_lanes = route_handler->getNextLanelets(extended_lanes.back());
if (!next_lanes.empty()) {
boost::optional<lanelet::ConstLanelet> target_next_lane;
if (!only_in_route) {
target_next_lane = next_lanes.front();
}
// use the next lane in route if it exists
auto target_next_lane = next_lanes.front();
for (const auto & next_lane : next_lanes) {
if (route_handler->isRouteLanelet(next_lane)) {
target_next_lane = next_lane;
}
}
extended_lanes.push_back(target_next_lane);
if (target_next_lane) {
extended_lanes.push_back(*target_next_lane);
}
}

return extended_lanes;
}

lanelet::ConstLanelets extendPrevLane(
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes)
const std::shared_ptr<RouteHandler> route_handler, const lanelet::ConstLanelets & lanes,
const bool only_in_route)
{
if (lanes.empty()) return lanes;

auto extended_lanes = lanes;

// Add previous lane
const auto prev_lanes = route_handler->getPreviousLanelets(extended_lanes.front());
if (!prev_lanes.empty()) {
boost::optional<lanelet::ConstLanelet> target_prev_lane;
if (!only_in_route) {
target_prev_lane = prev_lanes.front();
}
// use the previous lane in route if it exists
auto target_prev_lane = prev_lanes.front();
for (const auto & prev_lane : prev_lanes) {
if (route_handler->isRouteLanelet(prev_lane)) {
target_prev_lane = prev_lane;
}
}
extended_lanes.insert(extended_lanes.begin(), target_prev_lane);
if (target_prev_lane) {
extended_lanes.insert(extended_lanes.begin(), *target_prev_lane);
}
}
return extended_lanes;
}
Expand Down
Loading