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): make detection area dynamically #5303

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 @@ -118,8 +118,6 @@
object_ignore_section_crosswalk_in_front_distance: 30.0 # [m]
object_ignore_section_crosswalk_behind_distance: 30.0 # [m]
# detection range
object_check_forward_distance: 150.0 # [m]
object_check_backward_distance: 2.0 # [m]
object_check_goal_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
Expand All @@ -128,6 +126,13 @@
# lost object compensation
object_last_seen_threshold: 2.0

# detection area generation parameters
detection_area:
static: true # [-]
min_forward_distance: 50.0 # [m]
max_forward_distance: 150.0 # [m]
backward_distance: 10.0 # [m]

# For safety check
safety_check:
# safety check configuration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,9 +145,9 @@ struct AvoidanceParameters
double object_ignore_section_crosswalk_behind_distance{0.0};

// distance to avoid object detection
double object_check_forward_distance{0.0};

// continue to detect backward vehicles as avoidance targets until they are this distance away
bool use_static_detection_area{true};
double object_check_min_forward_distance{0.0};
double object_check_max_forward_distance{0.0};
double object_check_backward_distance{0.0};

// if the distance between object and goal position is less than this parameter, the module ignore
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,22 @@
: std::max(shift_length, getRightShiftBound());
}

double getForwardDetectionRange() const
{
if (parameters_->use_static_detection_area) {
return parameters_->object_check_max_forward_distance;
}

const auto max_shift_length = std::max(
std::abs(parameters_->max_right_shift_length), std::abs(parameters_->max_left_shift_length));
const auto dynamic_distance = PathShifter::calcLongitudinalDistFromJerk(

Check warning on line 184 in planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp#L184

Added line #L184 was not covered by tests
max_shift_length, getLateralMinJerkLimit(), getEgoSpeed());

return std::clamp(
1.5 * dynamic_distance, parameters_->object_check_min_forward_distance,

Check warning on line 188 in planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp#L188

Added line #L188 was not covered by tests
parameters_->object_check_max_forward_distance);
}

void alignShiftLinesOrder(AvoidLineArray & lines, const bool align_shift_length = true) const
{
if (lines.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const AvoidancePlanningData & data, const std::shared_ptr<AvoidanceParameters> & parameters,
const bool is_running, DebugData & debug);
const double object_check_forward_distance, const bool is_running, DebugData & debug);

DrivableLanes generateExpandDrivableLanes(
const lanelet::ConstLanelet & lanelet, const std::shared_ptr<const PlannerData> & planner_data,
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 2159 to 2160, 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 @@ -322,11 +322,12 @@
getCurrentStatus() == ModuleStatus::WAITING_APPROVAL;

// Separate dynamic objects based on whether they are inside or outside of the expanded lanelets.
const auto sparse_resample_path = utils::resamplePathWithSpline(
helper_.getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output);
const auto [object_within_target_lane, object_outside_target_lane] =
utils::avoidance::separateObjectsByPath(
utils::resamplePathWithSpline(
helper_.getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output),
planner_data_, data, parameters_, is_running, debug);
sparse_resample_path, planner_data_, data, parameters_, helper_.getForwardDetectionRange(),
is_running, debug);

for (const auto & object : object_outside_target_lane.objects) {
ObjectData other_object;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,23 +113,30 @@
p.object_ignore_section_crosswalk_in_front_distance = getOrDeclareParameter<double>(
*node, ns + "object_ignore_section_crosswalk_in_front_distance");
p.object_ignore_section_crosswalk_behind_distance =
getOrDeclareParameter<double>(*node, ns + "object_ignore_section_crosswalk_behind_distance");
p.object_check_forward_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_forward_distance");
p.object_check_backward_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_backward_distance");
p.object_check_goal_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_goal_distance");
p.threshold_distance_object_is_on_center =
getOrDeclareParameter<double>(*node, ns + "threshold_distance_object_is_on_center");
p.object_check_shiftable_ratio =
getOrDeclareParameter<double>(*node, ns + "object_check_shiftable_ratio");
p.object_check_min_road_shoulder_width =
getOrDeclareParameter<double>(*node, ns + "object_check_min_road_shoulder_width");
p.object_last_seen_threshold =
getOrDeclareParameter<double>(*node, ns + "object_last_seen_threshold");
}

{
std::string ns = "avoidance.target_filtering.detection_area.";
p.use_static_detection_area = getOrDeclareParameter<bool>(*node, ns + "static");
p.object_check_min_forward_distance =
getOrDeclareParameter<double>(*node, ns + "min_forward_distance");
p.object_check_max_forward_distance =
getOrDeclareParameter<double>(*node, ns + "max_forward_distance");
p.object_check_backward_distance =
getOrDeclareParameter<double>(*node, ns + "backward_distance");
}

Check warning on line 139 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 237 to 243. 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.
// safety check general params
{
std::string ns = "avoidance.safety_check.";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -328,23 +328,30 @@
p.object_ignore_section_crosswalk_in_front_distance = getOrDeclareParameter<double>(
*node, ns + "object_ignore_section_crosswalk_in_front_distance");
p.object_ignore_section_crosswalk_behind_distance =
getOrDeclareParameter<double>(*node, ns + "object_ignore_section_crosswalk_behind_distance");
p.object_check_forward_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_forward_distance");
p.object_check_backward_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_backward_distance");
p.object_check_goal_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_goal_distance");
p.threshold_distance_object_is_on_center =
getOrDeclareParameter<double>(*node, ns + "threshold_distance_object_is_on_center");
p.object_check_shiftable_ratio =
getOrDeclareParameter<double>(*node, ns + "object_check_shiftable_ratio");
p.object_check_min_road_shoulder_width =
getOrDeclareParameter<double>(*node, ns + "object_check_min_road_shoulder_width");
p.object_last_seen_threshold =
getOrDeclareParameter<double>(*node, ns + "object_last_seen_threshold");
}

{
std::string ns = "avoidance.target_filtering.detection_area.";
p.use_static_detection_area = getOrDeclareParameter<bool>(*node, ns + "static");
p.object_check_min_forward_distance =
getOrDeclareParameter<double>(*node, ns + "min_forward_distance");
p.object_check_max_forward_distance =
getOrDeclareParameter<double>(*node, ns + "max_forward_distance");
p.object_check_backward_distance =
getOrDeclareParameter<double>(*node, ns + "backward_distance");
}

Check warning on line 354 in planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager increases from 98 to 104 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.
// safety check
{
std::string ns = "avoidance.safety_check.";
Expand Down
8 changes: 4 additions & 4 deletions planning/behavior_path_planner/src/utils/avoidance/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -991,7 +991,7 @@
data.other_objects.push_back(o);
continue;
}
if (o.longitudinal > parameters->object_check_forward_distance) {
if (o.longitudinal > parameters->object_check_max_forward_distance) {
o.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD;
data.other_objects.push_back(o);
continue;
Expand Down Expand Up @@ -1479,7 +1479,7 @@
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift)
{
const auto & rh = planner_data->route_handler;
const auto & forward_distance = parameters->object_check_forward_distance;
const auto & forward_distance = parameters->object_check_max_forward_distance;
const auto & backward_distance = parameters->safety_check_backward_distance;
const auto & vehicle_pose = planner_data->self_odometry->pose.pose;

Expand Down Expand Up @@ -1619,30 +1619,30 @@
std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const AvoidancePlanningData & data, const std::shared_ptr<AvoidanceParameters> & parameters,
const bool is_running, DebugData & debug)
const double object_check_forward_distance, const bool is_running, DebugData & debug)
{
PredictedObjects target_objects;
PredictedObjects other_objects;

double max_offset = 0.0;
for (const auto & object_parameter : parameters->object_parameters) {
const auto p = object_parameter.second;
const auto offset =
2.0 * p.envelope_buffer_margin + p.safety_buffer_lateral + p.avoid_margin_lateral;
max_offset = std::max(max_offset, offset);
}

const auto detection_area =
createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset);
const auto ego_idx = planner_data->findEgoIndex(path.points);

Polygon2d attention_area;
for (size_t i = 0; i < path.points.size() - 1; ++i) {
const auto & p_ego_front = path.points.at(i).point.pose;
const auto & p_ego_back = path.points.at(i + 1).point.pose;

const auto distance_from_ego = calcSignedArcLength(path.points, ego_idx, i);
if (distance_from_ego > parameters->object_check_forward_distance) {
if (distance_from_ego > object_check_forward_distance) {

Check notice on line 1645 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Excess Number of Function Arguments

separateObjectsByPath increases from 6 to 7 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
break;
}

Expand Down
Loading