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(avoidance): add parameter to configurate avoidance return point #4467

Merged
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 @@ -160,6 +160,7 @@
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
remain_buffer_distance: 30.0 # [m]
min_prepare_distance: 1.0 # [m]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,9 @@ struct AvoidanceParameters
// nominal avoidance sped
double nominal_avoidance_speed;

// module try to return original path to keep this distance from edge point of the path.
double remain_buffer_distance;

// The margin is configured so that the generated avoidance trajectory does not come near to the
// road shoulder.
double road_shoulder_safety_margin{1.0};
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.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 2142 to 2143, 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 @@ -996,9 +996,10 @@
const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length;
// The end_margin also has the purpose of preventing the return path from NOT being
// triggered at the end point.
const auto end_margin = 1.0;
const auto return_remaining_distance =
std::max(data.arclength_from_ego.back() - o.longitudinal - offset - end_margin, 0.0);
const auto return_remaining_distance = std::max(

Check warning on line 999 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L999

Added line #L999 was not covered by tests
data.arclength_from_ego.back() - o.longitudinal - offset -
parameters_->remain_buffer_distance,
0.0);

Check notice on line 1002 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

AvoidanceModule::calcRawShiftLinesFromObjects already has high cyclomatic complexity, and now it increases in Lines of Code from 156 to 157. 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.

al_return.start_shift_length = feasible_shift_length.get();
al_return.end_shift_length = 0.0;
Expand Down Expand Up @@ -1745,14 +1746,14 @@
return;
}

const auto remaining_distance = arclength_from_ego.back();
const auto remaining_distance = arclength_from_ego.back() - parameters_->remain_buffer_distance;

// If the avoidance point has already been set, the return shift must be set after the point.
const auto last_sl_distance = avoidance_data_.arclength_from_ego.at(last_sl.end_idx);

// check if there is enough distance for return.
if (last_sl_distance + 1.0 > remaining_distance) { // tmp: add some small number (+1.0)
DEBUG_PRINT("No enough distance for return.");
if (last_sl_distance > remaining_distance) { // tmp: add some small number (+1.0)
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 1000, "No enough distance for return.");

Check warning on line 1756 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1756

Added line #L1756 was not covered by tests
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,7 @@
std::string ns = "avoidance.avoidance.longitudinal.";
p.prepare_time = get_parameter<double>(node, ns + "prepare_time");
p.min_prepare_distance = get_parameter<double>(node, ns + "min_prepare_distance");
p.remain_buffer_distance = get_parameter<double>(node, ns + "remain_buffer_distance");

Check warning on line 176 in planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AvoidanceModuleManager::AvoidanceModuleManager already has high cyclomatic complexity, and now it increases in Lines of Code from 180 to 181. 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.min_slow_down_speed = get_parameter<double>(node, ns + "min_slow_down_speed");
p.buf_slow_down_speed = get_parameter<double>(node, ns + "buf_slow_down_speed");
p.nominal_avoidance_speed = get_parameter<double>(node, ns + "nominal_avoidance_speed");
Expand Down
Loading