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): use different rss param to deal with parked vehicle #8316

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 @@ -709,6 +709,18 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |

#### safety constraints specifically for stopped or parked vehicles

| Name | Unit | Type | Description | Default value |
| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
| `safety_check.parked.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 |
| `safety_check.parked.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.0 |
| `safety_check.parked.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.0 |
| `safety_check.parked.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 |
| `safety_check.parked.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 |
| `safety_check.parked.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
| `safety_check.parked.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |

##### safety constraints to cancel lane change path

| Name | Unit | Type | Description | Default value |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,14 @@
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
parked:
expected_front_deceleration: -1.0
expected_rear_deceleration: -2.0
rear_vehicle_reaction_time: 1.0
rear_vehicle_safety_time_margin: 0.8
lateral_distance_max_threshold: 1.0
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.0
cancel:
expected_front_deceleration: -1.0
expected_rear_deceleration: -2.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,7 @@ struct Parameters
bool allow_loose_check_for_cancel{true};
double collision_check_yaw_diff_threshold{3.1416};
utils::path_safety_checker::RSSparams rss_params{};
utils::path_safety_checker::RSSparams rss_params_for_parked{};
utils::path_safety_checker::RSSparams rss_params_for_abort{};
utils::path_safety_checker::RSSparams rss_params_for_stuck{};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,23 @@
p.rss_params.lateral_distance_max_threshold = getOrDeclareParameter<double>(
*node, parameter("safety_check.execution.lateral_distance_max_threshold"));

p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
p.rss_params_for_parked.longitudinal_velocity_delta_time = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.longitudinal_velocity_delta_time"));
p.rss_params_for_parked.front_vehicle_deceleration = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.expected_front_deceleration"));
p.rss_params_for_parked.rear_vehicle_deceleration = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.expected_rear_deceleration"));
p.rss_params_for_parked.rear_vehicle_reaction_time = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.rear_vehicle_reaction_time"));
p.rss_params_for_parked.rear_vehicle_safety_time_margin = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.rear_vehicle_safety_time_margin"));
p.rss_params_for_parked.lateral_distance_max_threshold = getOrDeclareParameter<double>(
*node, parameter("safety_check.parked.lateral_distance_max_threshold"));

Check warning on line 141 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::initParams already has high cyclomatic complexity, and now it increases in Lines of Code from 199 to 215. 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.rss_params_for_abort.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
*node, parameter("safety_check.cancel.longitudinal_distance_min_threshold"));
p.rss_params_for_abort.longitudinal_velocity_delta_time = getOrDeclareParameter<double>(
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 1763 to 1768, 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.26 to 5.28, 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 @@ -2069,9 +2069,14 @@
const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj(
obj, lane_change_parameters_->use_all_predicted_path);
auto is_safe = true;
const auto selected_rss_param =
(obj.initial_twist.twist.linear.x <=
lane_change_parameters_->prepare_segment_ignore_object_velocity_thresh)

Check warning on line 2074 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#L2074

Added line #L2074 was not covered by tests
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

(minor) prepare_segment_ignore_object_velocity_thresh this parameter should probably be renamed since the object is not ignored (can be done in a future PR).

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, I plan to rename it to something else in the later PR.

? lane_change_parameters_->rss_params_for_parked
: rss_params;
for (const auto & obj_path : obj_predicted_paths) {
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
path, ego_predicted_path, obj, obj_path, common_parameters, selected_rss_param, 1.0,

Check warning on line 2079 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::isLaneChangePathSafe increases in cyclomatic complexity from 10 to 11, 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.
get_max_velocity_for_safety_check(), collision_check_yaw_diff_threshold,
current_debug_data.second);

Expand Down
Loading