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(lane_change): skip generating path if longitudinal distance difference is less than threshold #8363

Merged
Show file tree
Hide file tree
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
Expand Up @@ -26,6 +26,11 @@
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0

skip_process:
longitudinal_distance_diff_threshold:
prepare: 0.5
lane_changing: 0.5

# safety check
safety_check:
allow_loose_check_for_cancel: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ struct Parameters
double min_longitudinal_acc{-1.0};
double max_longitudinal_acc{1.0};

double skip_process_lon_diff_th_prepare{0.5};
double skip_process_lon_diff_th_lane_changing{1.0};

// collision check
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
bool enable_collision_check_for_prepare_phase_in_intersection{true};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -354,6 +354,13 @@
updateParam<double>(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc);
}

{
const std::string ns = "lane_change.skip_process.longitudinal_distance_diff_threshold.";
updateParam<double>(parameters, ns + "prepare", p->skip_process_lon_diff_th_prepare);
updateParam<double>(
parameters, ns + "lane_changing", p->skip_process_lon_diff_th_lane_changing);
}

Check warning on line 363 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

LaneChangeModuleManager::updateModuleParams increases from 93 to 99 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
{
const std::string ns = "lane_change.safety_check.lane_expansion.";
updateParam<double>(parameters, ns + "left_offset", p->lane_expansion_left_offset);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.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 1783 to 1802, 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/autoware_behavior_path_lane_change_module/src/scene.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 5.24 to 5.37, 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 @@ -1417,6 +1417,13 @@
continue;
}

if (!candidate_paths->empty()) {
const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length;
if (std::abs(prev_prep_diff) < lane_change_parameters_->skip_process_lon_diff_th_prepare) {
RCLCPP_DEBUG(logger_, "Skip: Change in prepare length is less than threshold.");
continue;

Check warning on line 1424 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L1424

Added line #L1424 was not covered by tests
}
}
auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length);

const auto debug_print = [&](const auto & s) {
Expand Down Expand Up @@ -1488,6 +1495,21 @@
lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing,
lane_changing_length);
};
if (!candidate_paths->empty()) {
const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length;

Check warning on line 1499 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L1499

Added line #L1499 was not covered by tests
const auto lc_length_diff =
candidate_paths->back().info.length.lane_changing - lane_changing_length;

// We only check lc_length_diff if and only if the current prepare_length is equal to the
// previous prepare_length.
if (
std::abs(prev_prep_diff) < eps &&
std::abs(lc_length_diff) <
lane_change_parameters_->skip_process_lon_diff_th_lane_changing) {
RCLCPP_DEBUG(logger_, "Skip: Change in lane changing length is less than threshold.");
continue;

Check warning on line 1510 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp#L1510

Added line #L1510 was not covered by tests
}
}

Check warning on line 1512 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

NormalLaneChange::getLaneChangePaths increases in cyclomatic complexity from 46 to 53, 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 1512 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Bumpy Road Ahead

NormalLaneChange::getLaneChangePaths increases from 4 to 5 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.

if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) {
debug_print_lat("Reject: length of lane changing path is longer than length to goal!!");
Expand Down
Loading