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(avoidance): fix avoidance exit condition #5592

Merged
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 planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.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 2203 to 2214, 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/scene_module/avoidance/avoidance_module.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.14 to 6.19, 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 @@ -222,6 +222,19 @@
const bool has_base_offset =
std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold;

// If the vehicle is on the shift line, keep RUNNING.
{
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);

Check warning on line 227 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L227

Added line #L227 was not covered by tests
const auto within = [](const auto & line, const size_t idx) {
return line.start_idx < idx && idx < line.end_idx;
};
for (const auto & shift_line : path_shifter_.getShiftLines()) {
if (within(shift_line, idx)) {
return false;
}
}
}

Check warning on line 237 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AvoidanceModule::canTransitSuccessState increases in cyclomatic complexity from 12 to 15, 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 237 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

AvoidanceModule::canTransitSuccessState increases from 2 to 3 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.
// Nothing to do. -> EXIT.
if (!has_avoidance_target) {
if (!has_shift_point && !has_base_offset) {
Expand Down
Loading