Skip to content

Commit f6a32e2

Browse files
committed
feat: find side lanelet of the next current lanelet
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 4cbf89a commit f6a32e2

File tree

1 file changed

+11
-1
lines changed

1 file changed

+11
-1
lines changed

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+11-1
Original file line numberDiff line numberDiff line change
@@ -1949,19 +1949,29 @@ std::vector<LaneletPathWithPathInfo> MapBasedPredictionNode::getPredictedReferen
19491949
return *opt;
19501950
}
19511951
if (!consider_only_routable_neighbours_) {
1952+
// 1. adjacent lanelet
19521953
const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet)
19531954
: routing_graph_ptr_->adjacentRight(lanelet);
19541955
if (!!adjacent) {
19551956
return *adjacent;
19561957
}
1957-
// search for unconnected lanelet
1958+
// 2. search for unconnected lanelet
19581959
const auto unconnected_lanelets =
19591960
get_left ? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_)
19601961
: getRightLineSharingLanelets(lanelet, lanelet_map_ptr_);
19611962
// just return first candidate of unconnected lanelet for now
19621963
if (!unconnected_lanelets.empty()) {
19631964
return unconnected_lanelets.front();
19641965
}
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+
}
19651975
}
19661976

19671977
// if no candidate lanelet found, return empty

0 commit comments

Comments
 (0)