Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(map_based_prediction): remove query on all fences linestrings #7237

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1895 to 1899, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 6.58 to 6.61, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -1309,10 +1309,14 @@

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
Loading