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

fix(avoidance): update filtering logic for non-vehicle #6206

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
1 change: 1 addition & 0 deletions planning/behavior_path_avoidance_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -557,6 +557,7 @@
addObjects(data.other_objects, std::string("TooNearToGoal"));
addObjects(data.other_objects, std::string("ParallelToEgoLane"));
addObjects(data.other_objects, std::string("MergingToEgoLane"));
addObjects(data.other_objects, std::string("UnstableObject"));

Check warning on line 560 in planning/behavior_path_avoidance_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

createDebugMarkerArray increases from 109 to 110 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.
}

// shift line pre-process
Expand Down
29 changes: 25 additions & 4 deletions planning/behavior_path_avoidance_module/src/utils.cpp
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_avoidance_module/src/utils.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 1745 to 1762, 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_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.35 to 5.33, 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 @@ -368,13 +368,15 @@
return parameters->object_parameters.at(object_type).is_safety_check_target;
}

bool isVehicleTypeObject(const ObjectData & object)
bool isUnknownTypeObject(const ObjectData & object)

Check warning on line 371 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L371

Added line #L371 was not covered by tests
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
return object_type == ObjectClassification::UNKNOWN;

Check warning on line 374 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L374

Added line #L374 was not covered by tests
}

if (object_type == ObjectClassification::UNKNOWN) {
return false;
}
bool isVehicleTypeObject(const ObjectData & object)

Check warning on line 377 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L377

Added line #L377 was not covered by tests
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);

Check warning on line 379 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L379

Added line #L379 was not covered by tests

if (object_type == ObjectClassification::PEDESTRIAN) {
return false;
Expand Down Expand Up @@ -723,6 +725,15 @@
return false;
}

// Object is on center line -> ignore.
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
object.to_centerline =

Check warning on line 730 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L729-L730

Added lines #L729 - L730 were not covered by tests
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {
object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
return false;

Check warning on line 734 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L733-L734

Added lines #L733 - L734 were not covered by tests
}

return true;
}

Expand Down Expand Up @@ -1626,6 +1637,16 @@
o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data);
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);

// TODO(Satoshi Ota) parametrize stop time threshold if need.
constexpr double STOP_TIME_THRESHOLD = 3.0; // [s]
if (filtering_utils::isUnknownTypeObject(o)) {
if (o.stop_time < STOP_TIME_THRESHOLD) {
o.reason = "UnstableObject";
data.other_objects.push_back(o);
continue;

Check warning on line 1646 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L1646

Added line #L1646 was not covered by tests
}
}

Check warning on line 1649 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

filterTargetObjects increases in cyclomatic complexity from 12 to 15, 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.

Check notice on line 1649 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

filterTargetObjects increases from 3 to 4 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) {
data.other_objects.push_back(o);
continue;
Expand Down
Loading