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

feat(blind_spot): consider road_shoulder if exist (autowarefoundation#7925) #1650

Merged
merged 1 commit into from
Nov 19, 2024
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 @@ -621,14 +621,14 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
for (const auto i : lane_ids) {
const auto lane = lanelet_map_ptr->laneletLayer.get(i);
const auto ego_half_lanelet = generateHalfLanelet(lane);
const auto adj =
const auto assoc_adj =
turn_direction_ == TurnDirection::LEFT
? (routing_graph_ptr->adjacentLeft(lane))
: (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane))
: boost::none);
const std::optional<lanelet::ConstLanelet> opposite_adj =
[&]() -> std::optional<lanelet::ConstLanelet> {
if (!!adj) {
if (!!assoc_adj) {
return std::nullopt;
}
if (turn_direction_ == TurnDirection::LEFT) {
Expand All @@ -653,10 +653,27 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
}
}();

if (!adj && !opposite_adj) {
blind_spot_lanelets.push_back(ego_half_lanelet);
} else if (!!adj) {
const auto adj_half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_);
const auto assoc_shoulder = [&]() -> std::optional<lanelet::ConstLanelet> {
if (turn_direction_ == TurnDirection::LEFT) {
return planner_data_->route_handler_->getLeftShoulderLanelet(lane);
} else if (turn_direction_ == TurnDirection::RIGHT) {
return planner_data_->route_handler_->getRightShoulderLanelet(lane);
}
return std::nullopt;
}();
if (assoc_shoulder) {
const auto lefts = (turn_direction_ == TurnDirection::LEFT)
? assoc_shoulder.value().leftBound()
: ego_half_lanelet.leftBound();
const auto rights = (turn_direction_ == TurnDirection::LEFT)
? ego_half_lanelet.rightBound()
: assoc_shoulder.value().rightBound();
blind_spot_lanelets.push_back(
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));

} else if (!!assoc_adj) {
const auto adj_half_lanelet =
generateExtendedAdjacentLanelet(assoc_adj.value(), turn_direction_);
const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound()
: ego_half_lanelet.leftBound();
const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound()
Expand All @@ -672,6 +689,8 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
: adj_half_lanelet.rightBound();
blind_spot_lanelets.push_back(
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));
} else {
blind_spot_lanelets.push_back(ego_half_lanelet);
}
}
return blind_spot_lanelets;
Expand Down
Loading