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

fix(utils): improve monotonic bound generation logic #4706

Merged
merged 1 commit into from
Aug 24, 2023
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
18 changes: 16 additions & 2 deletions planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021-2023 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/src/utils/utils.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 2590 to 2604, 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 planning/behavior_path_planner/src/utils/utils.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.00 to 6.03, 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 @@ -1755,8 +1755,22 @@
continue;
}

for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) {
set_orientation(ret, j, getPose(path_points.at(i)).orientation);
if (i + 1 == path_points.size()) {
for (size_t j = intersect_idx.get(); j < bound_with_pose.size(); j++) {
if (j + 1 == bound_with_pose.size()) {
const auto yaw =

Check warning on line 1761 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/utils.cpp#L1761

Added line #L1761 was not covered by tests
calcAzimuthAngle(bound_with_pose.at(j - 1).position, bound_with_pose.at(j).position);
set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw));
} else {
const auto yaw =
calcAzimuthAngle(bound_with_pose.at(j).position, bound_with_pose.at(j + 1).position);
set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw));
}

Check warning on line 1768 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/utils.cpp#L1768

Added line #L1768 was not covered by tests
}
} else {
for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) {
set_orientation(ret, j, getPose(path_points.at(i)).orientation);

Check warning on line 1772 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/utils.cpp#L1771-L1772

Added lines #L1771 - L1772 were not covered by tests
}

Check notice on line 1773 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

makeBoundLongitudinallyMonotonic increases from 5 to 7 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 1773 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

makeBoundLongitudinallyMonotonic increases in cyclomatic complexity from 36 to 39, 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 warning on line 1773 in planning/behavior_path_planner/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

makeBoundLongitudinallyMonotonic 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.
}

constexpr size_t OVERLAP_CHECK_NUM = 3;
Expand Down
Loading