@@ -266,8 +266,8 @@ Result<IntersectionModule::BasicData, InternalError> IntersectionModule::prepare
266
266
267
267
if (!occlusion_attention_divisions_) {
268
268
occlusion_attention_divisions_ = generateDetectionLaneDivisions (
269
- intersection_lanelets.occlusion_attention (), routing_graph_ptr ,
270
- planner_data_->occupancy_grid ->info .resolution );
269
+ intersection_lanelets.occlusion_attention (), intersection_lanelets. attention_non_preceding () ,
270
+ routing_graph_ptr, planner_data_->occupancy_grid ->info .resolution );
271
271
}
272
272
273
273
if (has_traffic_light_) {
@@ -577,6 +577,73 @@ std::optional<IntersectionStopLines> IntersectionModule::generateIntersectionSto
577
577
return intersection_stoplines;
578
578
}
579
579
580
+ static std::vector<std::deque<lanelet::ConstLanelet>> getPrecedingLaneletsUptoIntersectionRecursive (
581
+ const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
582
+ const double length, const lanelet::ConstLanelets & exclude_lanelets)
583
+ {
584
+ std::vector<std::deque<lanelet::ConstLanelet>> preceding_lanelet_sequences;
585
+
586
+ const auto prev_lanelets = graph->previous (lanelet);
587
+ const double lanelet_length = lanelet::utils::getLaneletLength3d (lanelet);
588
+
589
+ // end condition of the recursive function
590
+ if (prev_lanelets.empty () || lanelet_length >= length) {
591
+ preceding_lanelet_sequences.push_back ({lanelet});
592
+ return preceding_lanelet_sequences;
593
+ }
594
+
595
+ for (const auto & prev_lanelet : prev_lanelets) {
596
+ if (lanelet::utils::contains (exclude_lanelets, prev_lanelet)) {
597
+ // if prev_lanelet is included in exclude_lanelets,
598
+ // remove prev_lanelet from preceding_lanelet_sequences
599
+ continue ;
600
+ }
601
+ if (const std::string turn_direction = prev_lanelet.attributeOr (" turn_direction" , " else" );
602
+ turn_direction == " left" || turn_direction == " right" ) {
603
+ continue ;
604
+ }
605
+
606
+ // get lanelet sequence after prev_lanelet
607
+ auto tmp_lanelet_sequences = getPrecedingLaneletsUptoIntersectionRecursive (
608
+ graph, prev_lanelet, length - lanelet_length, exclude_lanelets);
609
+ for (auto & tmp_lanelet_sequence : tmp_lanelet_sequences) {
610
+ tmp_lanelet_sequence.push_back (lanelet);
611
+ preceding_lanelet_sequences.push_back (tmp_lanelet_sequence);
612
+ }
613
+ }
614
+
615
+ if (preceding_lanelet_sequences.empty ()) {
616
+ preceding_lanelet_sequences.push_back ({lanelet});
617
+ }
618
+ return preceding_lanelet_sequences;
619
+ }
620
+
621
+ static std::vector<lanelet::ConstLanelets> getPrecedingLaneletsUptoIntersection (
622
+ const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
623
+ const double length, const lanelet::ConstLanelets & exclude_lanelets)
624
+ {
625
+ std::vector<lanelet::ConstLanelets> lanelet_sequences_vec;
626
+ const auto prev_lanelets = graph->previous (lanelet);
627
+ for (const auto & prev_lanelet : prev_lanelets) {
628
+ if (lanelet::utils::contains (exclude_lanelets, prev_lanelet)) {
629
+ // if prev_lanelet is included in exclude_lanelets,
630
+ // remove prev_lanelet from preceding_lanelet_sequences
631
+ continue ;
632
+ }
633
+ if (const std::string turn_direction = prev_lanelet.attributeOr (" turn_direction" , " else" );
634
+ turn_direction == " left" || turn_direction == " right" ) {
635
+ continue ;
636
+ }
637
+ // convert deque into vector
638
+ const auto lanelet_sequences_deq =
639
+ getPrecedingLaneletsUptoIntersectionRecursive (graph, prev_lanelet, length, exclude_lanelets);
640
+ for (const auto & lanelet_sequence : lanelet_sequences_deq) {
641
+ lanelet_sequences_vec.emplace_back (lanelet_sequence.begin (), lanelet_sequence.end ());
642
+ }
643
+ }
644
+ return lanelet_sequences_vec;
645
+ }
646
+
580
647
IntersectionLanelets IntersectionModule::generateObjectiveLanelets (
581
648
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
582
649
const lanelet::ConstLanelet assigned_lanelet) const
@@ -706,8 +773,8 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
706
773
if (inserted.second ) occlusion_detection_and_preceding_lanelets.push_back (ll);
707
774
// get preceding lanelets without ego_lanelets
708
775
// to prevent the detection area from including the ego lanes and its' preceding lanes.
709
- const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences (
710
- routing_graph_ptr, ll, length, ego_lanelets);
776
+ const auto lanelet_sequences =
777
+ getPrecedingLaneletsUptoIntersection ( routing_graph_ptr, ll, length, ego_lanelets);
711
778
for (const auto & ls : lanelet_sequences) {
712
779
for (const auto & l : ls) {
713
780
const auto & inserted = detection_ids.insert (l.id ());
@@ -716,17 +783,10 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
716
783
}
717
784
}
718
785
}
719
- lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets_wo_turn_direction;
720
- for (const auto & ll : occlusion_detection_and_preceding_lanelets) {
721
- const std::string turn_direction = ll.attributeOr (" turn_direction" , " else" );
722
- if (turn_direction == " left" || turn_direction == " right" ) {
723
- continue ;
724
- }
725
- occlusion_detection_and_preceding_lanelets_wo_turn_direction.push_back (ll);
726
- }
727
786
728
787
auto [attention_lanelets, original_attention_lanelet_sequences] =
729
- util::mergeLaneletsByTopologicalSort (detection_and_preceding_lanelets, routing_graph_ptr);
788
+ util::mergeLaneletsByTopologicalSort (
789
+ detection_and_preceding_lanelets, detection_lanelets, routing_graph_ptr);
730
790
731
791
IntersectionLanelets result;
732
792
result.attention_ = std::move (attention_lanelets);
@@ -764,8 +824,7 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
764
824
// NOTE: occlusion_attention is not inverted here
765
825
// TODO(Mamoru Sobue): apply mergeLaneletsByTopologicalSort for occlusion lanelets as well and
766
826
// then trim part of them based on curvature threshold
767
- result.occlusion_attention_ =
768
- std::move (occlusion_detection_and_preceding_lanelets_wo_turn_direction);
827
+ result.occlusion_attention_ = std::move (occlusion_detection_and_preceding_lanelets);
769
828
770
829
// NOTE: to properly update(), each element in conflicting_/conflicting_area_,
771
830
// attention_non_preceding_/attention_non_preceding_area_ need to be matched
@@ -851,7 +910,8 @@ std::optional<PathLanelets> IntersectionModule::generatePathLanelets(
851
910
}
852
911
853
912
std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLaneDivisions (
854
- lanelet::ConstLanelets detection_lanelets_all,
913
+ const lanelet::ConstLanelets & occlusion_detection_lanelets,
914
+ const lanelet::ConstLanelets & conflicting_detection_lanelets,
855
915
const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) const
856
916
{
857
917
const double curvature_threshold =
@@ -861,9 +921,9 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
861
921
862
922
using lanelet::utils::getCenterlineWithOffset;
863
923
864
- // (0) remove left/right lanelet
924
+ // (0) remove curved
865
925
lanelet::ConstLanelets detection_lanelets;
866
- for (const auto & detection_lanelet : detection_lanelets_all ) {
926
+ for (const auto & detection_lanelet : occlusion_detection_lanelets ) {
867
927
// TODO(Mamoru Sobue): instead of ignoring, only trim straight part of lanelet
868
928
const auto fine_centerline =
869
929
lanelet::utils::generateFineCenterline (detection_lanelet, curvature_calculation_ds);
@@ -874,9 +934,17 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
874
934
detection_lanelets.push_back (detection_lanelet);
875
935
}
876
936
937
+ std::vector<lanelet::ConstLineString3d> detection_divisions;
938
+ if (detection_lanelets.empty ()) {
939
+ // NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain
940
+ // conflicting_detection_lanelets
941
+ // OK to return empty detction_divsions
942
+ return detection_divisions;
943
+ }
944
+
877
945
// (1) tsort detection_lanelets
878
- const auto [merged_detection_lanelets, originals] =
879
- util::mergeLaneletsByTopologicalSort ( detection_lanelets, routing_graph_ptr);
946
+ const auto [merged_detection_lanelets, originals] = util::mergeLaneletsByTopologicalSort (
947
+ detection_lanelets, conflicting_detection_lanelets , routing_graph_ptr);
880
948
881
949
// (2) merge each branch to one lanelet
882
950
// NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here
@@ -892,7 +960,6 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
892
960
}
893
961
894
962
// (3) discretize each merged lanelet
895
- std::vector<lanelet::ConstLineString3d> detection_divisions;
896
963
for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) {
897
964
const double length = bg::length (merged_lanelet.centerline ());
898
965
const double width = area / length;
0 commit comments