Skip to content

Commit

Permalink
different rss value for parked vehicle
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 committed Aug 2, 2024
1 parent c7432e1 commit b5e22ea
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 1 deletion.
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 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
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
Expand Up @@ -2069,9 +2069,14 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
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)
? 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

0 comments on commit b5e22ea

Please sign in to comment.