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

refactor(lane_change): add missing safety check parameter #9928

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 @@ -1149,6 +1149,7 @@ The following parameters are used to configure terminal lane change path feature
| `collision_check.use_all_predicted_paths` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true |
| `collision_check.prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 |
| `collision_check.yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 |
| `collision_check.th_incoming_object_yaw` | [rad] | double | Objects with a heading difference from the ego exceeding this value are excluded from the safety check. | 2.3562 |
zulfaqar-azmi-t4 marked this conversation as resolved.
Show resolved Hide resolved

#### safety constraints during lane change path is computed

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,8 @@
intersection: true
turns: true
prediction_time_resolution: 0.5
yaw_diff_threshold: 3.1416
th_incoming_object_yaw: 2.3562 # [rad]
yaw_diff_threshold: 3.1416 # [rad]
check_current_lanes: false
check_other_lanes: false
use_all_predicted_paths: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ struct CollisionCheckParameters
bool check_current_lane{true};
bool check_other_lanes{true};
bool use_all_predicted_paths{false};
double th_incoming_object_yaw{2.3562};
double th_yaw_diff{3.1416};
double prediction_time_resolution{0.5};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,8 @@
getOrDeclareParameter<double>(*node, parameter("collision_check.prediction_time_resolution"));
p.safety.collision_check.th_yaw_diff =
getOrDeclareParameter<double>(*node, parameter("collision_check.yaw_diff_threshold"));
p.safety.collision_check.th_incoming_object_yaw =
getOrDeclareParameter<double>(*node, parameter("collision_check.th_incoming_object_yaw"));

Check warning on line 156 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 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.

// rss check
auto set_rss_params = [&](auto & params, const std::string & prefix) {
Expand Down Expand Up @@ -440,6 +442,18 @@
p->safety.collision_check.prediction_time_resolution);
updateParam<double>(
parameters, ns + "yaw_diff_threshold", p->safety.collision_check.th_yaw_diff);

auto th_incoming_object_yaw = p->safety.collision_check.th_incoming_object_yaw;
updateParam<double>(parameters, ns + "th_incoming_object_yaw", th_incoming_object_yaw);
if (th_incoming_object_yaw >= M_PI_2) {
p->safety.collision_check.th_incoming_object_yaw = th_incoming_object_yaw;
} else {
RCLCPP_WARN_THROTTLE(

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp#L451

Added line #L451 was not covered by tests
node_->get_logger(), *node_->get_clock(), 5000,
"The value of th_incoming_object_yaw (%.3f rad) is less than the minimum possible value (%.3f "
"rad).",
th_incoming_object_yaw, M_PI_2);
}

Check warning on line 456 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::updateModuleParams increases in cyclomatic complexity from 11 to 12, 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.
}

{
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 1531, 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.
//
// 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 @@ -1051,7 +1051,9 @@

const auto is_same_direction = [&](const PredictedObject & object) {
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
return !utils::path_safety_checker::isTargetObjectOncoming(current_pose, object_pose);
return !utils::path_safety_checker::isTargetObjectOncoming(
current_pose, object_pose,
common_data_ptr_->lc_param_ptr->safety.collision_check.th_incoming_object_yaw);
};

// Perception noise could make stationary objects seem opposite the ego vehicle; check the
Expand Down
Loading