Skip to content

Commit ad0ae45

Browse files
soblinTomohitoAndo
authored andcommitted
feat(blind_spot): consider road_shoulder if exist (autowarefoundation#7925)
Signed-off-by: Mamoru Sobue <[email protected]>
1 parent 9db907a commit ad0ae45

File tree

1 file changed

+25
-6
lines changed
  • planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src

1 file changed

+25
-6
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp

Lines changed: 25 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -621,14 +621,14 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
621621
for (const auto i : lane_ids) {
622622
const auto lane = lanelet_map_ptr->laneletLayer.get(i);
623623
const auto ego_half_lanelet = generateHalfLanelet(lane);
624-
const auto adj =
624+
const auto assoc_adj =
625625
turn_direction_ == TurnDirection::LEFT
626626
? (routing_graph_ptr->adjacentLeft(lane))
627627
: (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane))
628628
: boost::none);
629629
const std::optional<lanelet::ConstLanelet> opposite_adj =
630630
[&]() -> std::optional<lanelet::ConstLanelet> {
631-
if (!!adj) {
631+
if (!!assoc_adj) {
632632
return std::nullopt;
633633
}
634634
if (turn_direction_ == TurnDirection::LEFT) {
@@ -653,10 +653,27 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
653653
}
654654
}();
655655

656-
if (!adj && !opposite_adj) {
657-
blind_spot_lanelets.push_back(ego_half_lanelet);
658-
} else if (!!adj) {
659-
const auto adj_half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_);
656+
const auto assoc_shoulder = [&]() -> std::optional<lanelet::ConstLanelet> {
657+
if (turn_direction_ == TurnDirection::LEFT) {
658+
return planner_data_->route_handler_->getLeftShoulderLanelet(lane);
659+
} else if (turn_direction_ == TurnDirection::RIGHT) {
660+
return planner_data_->route_handler_->getRightShoulderLanelet(lane);
661+
}
662+
return std::nullopt;
663+
}();
664+
if (assoc_shoulder) {
665+
const auto lefts = (turn_direction_ == TurnDirection::LEFT)
666+
? assoc_shoulder.value().leftBound()
667+
: ego_half_lanelet.leftBound();
668+
const auto rights = (turn_direction_ == TurnDirection::LEFT)
669+
? ego_half_lanelet.rightBound()
670+
: assoc_shoulder.value().rightBound();
671+
blind_spot_lanelets.push_back(
672+
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));
673+
674+
} else if (!!assoc_adj) {
675+
const auto adj_half_lanelet =
676+
generateExtendedAdjacentLanelet(assoc_adj.value(), turn_direction_);
660677
const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound()
661678
: ego_half_lanelet.leftBound();
662679
const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound()
@@ -672,6 +689,8 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
672689
: adj_half_lanelet.rightBound();
673690
blind_spot_lanelets.push_back(
674691
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));
692+
} else {
693+
blind_spot_lanelets.push_back(ego_half_lanelet);
675694
}
676695
}
677696
return blind_spot_lanelets;

0 commit comments

Comments
 (0)