Skip to content

Commit

Permalink
Merge pull request #1860 from tier4/cherry-pick-10138
Browse files Browse the repository at this point in the history
fix(route_handler): use non-preferred route segment even if checkpoint is not on preferred lanelet at best (autowarefoundation#10138)
  • Loading branch information
SakodaShintaro authored Feb 25, 2025
2 parents 453899d + 2c8522c commit 51efaba
Showing 1 changed file with 16 additions and 0 deletions.
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

0 comments on commit 51efaba

Please sign in to comment.