@@ -621,14 +621,14 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
621
621
for (const auto i : lane_ids) {
622
622
const auto lane = lanelet_map_ptr->laneletLayer .get (i);
623
623
const auto ego_half_lanelet = generateHalfLanelet (lane);
624
- const auto adj =
624
+ const auto assoc_adj =
625
625
turn_direction_ == TurnDirection::LEFT
626
626
? (routing_graph_ptr->adjacentLeft (lane))
627
627
: (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight (lane))
628
628
: boost::none);
629
629
const std::optional<lanelet::ConstLanelet> opposite_adj =
630
630
[&]() -> std::optional<lanelet::ConstLanelet> {
631
- if (!!adj ) {
631
+ if (!!assoc_adj ) {
632
632
return std::nullopt;
633
633
}
634
634
if (turn_direction_ == TurnDirection::LEFT) {
@@ -653,10 +653,27 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
653
653
}
654
654
}();
655
655
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_);
660
677
const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound ()
661
678
: ego_half_lanelet.leftBound ();
662
679
const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound ()
@@ -672,6 +689,8 @@ lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets(
672
689
: adj_half_lanelet.rightBound ();
673
690
blind_spot_lanelets.push_back (
674
691
lanelet::ConstLanelet (lanelet::InvalId, removeConst (lefts), removeConst (rights)));
692
+ } else {
693
+ blind_spot_lanelets.push_back (ego_half_lanelet);
675
694
}
676
695
}
677
696
return blind_spot_lanelets;
0 commit comments