File tree 1 file changed +11
-1
lines changed
perception/autoware_map_based_prediction/src
1 file changed +11
-1
lines changed Original file line number Diff line number Diff line change @@ -1949,19 +1949,29 @@ std::vector<LaneletPathWithPathInfo> MapBasedPredictionNode::getPredictedReferen
1949
1949
return *opt;
1950
1950
}
1951
1951
if (!consider_only_routable_neighbours_) {
1952
+ // 1. adjacent lanelet
1952
1953
const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft (lanelet)
1953
1954
: routing_graph_ptr_->adjacentRight (lanelet);
1954
1955
if (!!adjacent) {
1955
1956
return *adjacent;
1956
1957
}
1957
- // search for unconnected lanelet
1958
+ // 2. search for unconnected lanelet
1958
1959
const auto unconnected_lanelets =
1959
1960
get_left ? getLeftLineSharingLanelets (lanelet, lanelet_map_ptr_)
1960
1961
: getRightLineSharingLanelets (lanelet, lanelet_map_ptr_);
1961
1962
// just return first candidate of unconnected lanelet for now
1962
1963
if (!unconnected_lanelets.empty ()) {
1963
1964
return unconnected_lanelets.front ();
1964
1965
}
1966
+ // 3. search side of the next lanelet
1967
+ const lanelet::ConstLanelets next_lanelet = routing_graph_ptr_->following (lanelet);
1968
+ if (!next_lanelet.empty ()) {
1969
+ const auto next = get_left ? routing_graph_ptr_->left (next_lanelet.front ())
1970
+ : routing_graph_ptr_->right (next_lanelet.front ());
1971
+ if (!!next) {
1972
+ return *next;
1973
+ }
1974
+ }
1965
1975
}
1966
1976
1967
1977
// if no candidate lanelet found, return empty
You can’t perform that action at this time.
0 commit comments