Skip to content

Commit

Permalink
perf(map_based_prediction): remove query on all fences linestrings (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#7237)

Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem authored and Ariiees committed Jul 22, 2024
1 parent 765a656 commit 8c746ed
Showing 1 changed file with 8 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1309,10 +1309,14 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared(

bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path)
{
const lanelet::ConstLineStrings3d & all_fences =
lanelet::utils::query::getAllFences(lanelet_map_ptr_);
for (const auto & fence_line : all_fences) {
if (doesPathCrossFence(predicted_path, fence_line)) {
lanelet::BasicLineString2d predicted_path_ls;
for (const auto & p : predicted_path.path)
predicted_path_ls.emplace_back(p.position.x, p.position.y);
const auto candidates =
lanelet_map_ptr_->lineStringLayer.search(lanelet::geometry::boundingBox2d(predicted_path_ls));
for (const auto & candidate : candidates) {
const std::string type = candidate.attributeOr(lanelet::AttributeName::Type, "none");
if (type == "fence" && doesPathCrossFence(predicted_path, candidate)) {
return true;
}
}
Expand Down

0 comments on commit 8c746ed

Please sign in to comment.