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(lane_change): ensure path generation doesn't exceed time limit #9908

Merged
Show file tree
Hide file tree
Changes from 3 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 @@ -1039,6 +1039,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi

| Name | Unit | Type | Description | Default value |
| :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ |
| `time_limit` | [ms] | double | Time limit for lane change candidate path generation | 50.0 |
| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 |
| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 |
| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 |
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/**:
ros__parameters:
lane_change:
time_limit: 50.0 # [ms]
backward_lane_length: 200.0
backward_length_buffer_for_end_of_lane: 3.0 # [m]
backward_length_buffer_for_blocking_object: 3.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,7 @@ struct Parameters
FrenetPlannerParameters frenet{};

// lane change parameters
double time_limit{50.0};
double backward_lane_length{200.0};
double backward_length_buffer_for_end_of_lane{0.0};
double backward_length_buffer_for_blocking_object{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@
}

// lane change parameters
p.time_limit = getOrDeclareParameter<double>(*node, parameter("time_limit"));

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

LaneChangeModuleManager::set_params already has high cyclomatic complexity, and now it increases in Lines of Code from 213 to 214. 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.
p.backward_lane_length = getOrDeclareParameter<double>(*node, parameter("backward_lane_length"));
p.backward_length_buffer_for_end_of_lane =
getOrDeclareParameter<double>(*node, parameter("backward_length_buffer_for_end_of_lane"));
Expand Down Expand Up @@ -313,6 +314,7 @@

{
const std::string ns = "lane_change.";
updateParam<double>(parameters, ns + "time_limit", p->time_limit);

Check warning on line 317 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 115 to 116 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.
mkquda marked this conversation as resolved.
Show resolved Hide resolved
updateParam<double>(parameters, ns + "backward_lane_length", p->backward_lane_length);
updateParam<double>(
parameters, ns + "backward_length_buffer_for_end_of_lane",
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 1529 to 1537, 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 4.94 to 4.98, 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 @@ -1154,18 +1154,22 @@
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
LaneChangePaths & candidate_paths) const
{
stop_watch_.tic("frenet_candidates");
stop_watch_.tic(__func__);

Check warning on line 1157 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#L1157

Added line #L1157 was not covered by tests
constexpr auto found_safe_path = true;
const auto frenet_candidates = utils::lane_change::generate_frenet_candidates(
common_data_ptr_, prev_module_output_.path, prepare_metrics);
RCLCPP_DEBUG(
logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(),
stop_watch_.toc("frenet_candidates"));
stop_watch_.toc(__func__));

candidate_paths.reserve(frenet_candidates.size());
lane_change_debug_.frenet_states.clear();
lane_change_debug_.frenet_states.reserve(frenet_candidates.size());
for (const auto & frenet_candidate : frenet_candidates) {
if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) {
break;
}

lane_change_debug_.frenet_states.emplace_back(
frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter,
frenet_candidate.max_lane_changing_length);
Expand All @@ -1186,7 +1190,7 @@
if (check_candidate_path_safety(*candidate_path_opt, target_objects)) {
RCLCPP_DEBUG(
logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]",
frenet_candidates.size(), stop_watch_.toc("frenet_candidates"));
frenet_candidates.size(), stop_watch_.toc("__func__"));
utils::lane_change::append_target_ref_to_candidate(
*candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing);
candidate_paths.push_back(*candidate_path_opt);
Expand All @@ -1204,7 +1208,7 @@

RCLCPP_DEBUG(
logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(),
stop_watch_.toc("frenet_candidates"));
stop_watch_.toc(__func__));

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

❌ New issue: Complex Method

NormalLaneChange::get_path_using_frenet has a cyclomatic complexity of 9, 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.
return !found_safe_path;
}

Expand All @@ -1214,71 +1218,77 @@
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
LaneChangePaths & candidate_paths) const
{
stop_watch_.tic(__func__);
const auto & target_lanes = get_target_lanes();
candidate_paths.reserve(
prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num);

const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time;
const auto dist_to_next_regulatory_element =
utils::lane_change::get_distance_to_next_regulatory_element(common_data_ptr_, only_tl, only_tl);

auto check_length_diff =
[&](const double prep_length, const double lc_length, const bool check_lc) {
if (candidate_paths.empty()) return true;

const auto prep_diff = std::abs(candidate_paths.back().info.length.prepare - prep_length);
if (prep_diff > lane_change_parameters_->trajectory.th_prepare_length_diff) return true;

if (!check_lc) return false;

const auto lc_diff = std::abs(candidate_paths.back().info.length.lane_changing - lc_length);
return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff;
};

for (const auto & prep_metric : prepare_metrics) {
const auto debug_print = [&](const std::string & s) {
RCLCPP_DEBUG(
logger_, "%s | prep_time: %.5f | lon_acc: %.5f | prep_len: %.5f", s.c_str(),
prep_metric.duration, prep_metric.actual_lon_accel, prep_metric.length);
};

if (!check_length_diff(prep_metric.length, 0.0, false)) {
RCLCPP_DEBUG(logger_, "Skip: Change in prepare length is less than threshold.");
continue;
}

PathWithLaneId prepare_segment;
try {
if (!utils::lane_change::get_prepare_segment(
common_data_ptr_, prev_module_output_.path, prep_metric.length, prepare_segment)) {
debug_print("Reject: failed to get valid prepare segment!");
continue;
}
} catch (const std::exception & e) {
debug_print(e.what());
break;
}

debug_print("Prepare path satisfy constraints");

const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose;

const auto shift_length =
lanelet::utils::getLateralDistanceToClosestLanelet(target_lanes, lane_changing_start_pose);

lane_change_debug_.lane_change_metrics.emplace_back();
auto & debug_metrics = lane_change_debug_.lane_change_metrics.back();
debug_metrics.prep_metric = prep_metric;
debug_metrics.max_prepare_length = common_data_ptr_->transient_data.dist_to_terminal_start;
const auto lane_changing_metrics = get_lane_changing_metrics(
prepare_segment, prep_metric, shift_length, dist_to_next_regulatory_element, debug_metrics);

// set_prepare_velocity must only be called after computing lane change metrics, as lane change
// metrics rely on the prepare segment's original velocity as max_path_velocity.
utils::lane_change::set_prepare_velocity(
prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity);

for (const auto & lc_metric : lane_changing_metrics) {
if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) {
RCLCPP_DEBUG(logger_, "Time limit reached and no safe path was found.");
return false;
}

Check warning on line 1291 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::get_path_using_path_shifter increases in cyclomatic complexity from 17 to 18, 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.
debug_metrics.lc_metrics.emplace_back(lc_metric, -1);

const auto debug_print_lat = [&](const std::string & s) {
Expand Down
Loading