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

feat(autoware_map_based_prediction): find side lanelet of the next current lanelet #9095

Draft
wants to merge 1 commit into
base: main
Choose a base branch
from
Draft
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 2096 to 2104, 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 7.31 to 7.36, 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 @@ -2037,19 +2037,29 @@
return *opt;
}
if (!consider_only_routable_neighbours_) {
// 1. adjacent lanelet
const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet)
: routing_graph_ptr_->adjacentRight(lanelet);
if (!!adjacent) {
return *adjacent;
}
// search for unconnected lanelet
// 2. search for unconnected lanelet
const auto unconnected_lanelets =
get_left ? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_)
: getRightLineSharingLanelets(lanelet, lanelet_map_ptr_);
// just return first candidate of unconnected lanelet for now
if (!unconnected_lanelets.empty()) {
return unconnected_lanelets.front();
}
// 3. search side of the next lanelet
const lanelet::ConstLanelets next_lanelet = routing_graph_ptr_->following(lanelet);
if (!next_lanelet.empty()) {
const auto next = get_left ? routing_graph_ptr_->left(next_lanelet.front())
: routing_graph_ptr_->right(next_lanelet.front());
if (!!next) {
return *next;
}
}

Check warning on line 2062 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: Complex Method

MapBasedPredictionNode::getPredictedReferencePath increases in cyclomatic complexity from 27 to 30, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 2062 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: Bumpy Road Ahead

MapBasedPredictionNode::getPredictedReferencePath increases from 3 to 4 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check warning on line 2062 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)

❌ New issue: Deep, Nested Complexity

MapBasedPredictionNode::getPredictedReferencePath has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
}

// if no candidate lanelet found, return empty
Expand Down
Loading