From 7bc6a4e109cfaafc44ec3cae2cf5ab44ed7190a4 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Fri, 17 Jan 2025 13:53:12 +0900 Subject: [PATCH] fix(map_based_prediction): fix unintentional accumulation of lanelets (#9950) add clear before insert Signed-off-by: a-maumau --- perception/autoware_map_based_prediction/src/predictor_vru.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_map_based_prediction/src/predictor_vru.cpp b/perception/autoware_map_based_prediction/src/predictor_vru.cpp index 0eea665cbd8a2..ffbdbd97b50a2 100644 --- a/perception/autoware_map_based_prediction/src/predictor_vru.cpp +++ b/perception/autoware_map_based_prediction/src/predictor_vru.cpp @@ -269,6 +269,7 @@ void PredictorVru::setLaneletMap(std::shared_ptr lanelet_ma const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); const auto crosswalks = lanelet::utils::query::crosswalkLanelets(all_lanelets); const auto walkways = lanelet::utils::query::walkwayLanelets(all_lanelets); + crosswalks_.clear(); crosswalks_.insert(crosswalks_.end(), crosswalks.begin(), crosswalks.end()); crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end());