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(route_handler): use non-preferred route segment even if checkpoint is not on preferred lanelet at best (#10138) #1860

Merged
merged 1 commit into from
Feb 25, 2025
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
16 changes: 16 additions & 0 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1929,6 +1929,22 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
}
}
}
if (getClosestLaneletWithinRoute(goal_checkpoint, &closest_lanelet)) {
if (std::find(candidates.begin(), candidates.end(), closest_lanelet) != candidates.end()) {
if (lanelet::utils::isInLanelet(goal_checkpoint, closest_lanelet)) {
std::stringstream preferred_lanelets_str;
for (const auto & preferred_lanelet : preferred_lanelets_) {
preferred_lanelets_str << preferred_lanelet.id() << ", ";
}
RCLCPP_WARN(
logger_,
"Failed to find reroute on previous preferred lanelets %s, but on previous route "
"segment %ld still",
preferred_lanelets_str.str().c_str(), closest_lanelet.id());
return closest_lanelet;
}
}
}
return std::nullopt;
};
if (auto closest_lanelet = findGoalClosestPreferredLanelet()) {
Expand Down
Loading