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(static_obstacle_avoidance): don't automatically avoid ambiguous vehicle #7851

Merged
merged 2 commits into from
Jul 10, 2024
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 @@ -137,9 +137,11 @@

{
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter<bool>(*node, ns + "enable");
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "closest_distance_to_wait_and_see");
p.policy_ambiguous_vehicle = getOrDeclareParameter<std::string>(*node, ns + "policy");
p.wait_and_see_target_behaviors =
getOrDeclareParameter<std::vector<std::string>>(*node, ns + "wait_and_see.target_behaviors");
p.wait_and_see_th_closest_distance =
getOrDeclareParameter<double>(*node, ns + "wait_and_see.th_closest_distance");

Check warning on line 144 in planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

AvoidanceByLaneChangeModuleManager::init increases from 129 to 131 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.
p.time_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.th_stopped_time");
p.distance_threshold_for_ambiguous_vehicle =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,8 +138,11 @@

# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
avoidance_for_ambiguous_vehicle:
enable: true # [-]
closest_distance_to_wait_and_see: 10.0 # [m]
# policy for ego behavior for ambiguous vehicle.
# "auto" : generate candidate path. if RTC is running as AUTO mode, the ego avoids it automatically.
# "manual" : generate candidate path and wait operator approval even if RTC is running as AUTO mode.
# "ignore" : never avoid it.
policy: "auto" # [-]
condition:
th_stopped_time: 3.0 # [s]
th_moving_distance: 1.0 # [m]
Expand All @@ -149,6 +152,9 @@
crosswalk:
front_distance: 30.0 # [m]
behind_distance: 30.0 # [m]
wait_and_see:
target_behaviors: ["MERGING", "DEVIATING"] # [-]
th_closest_distance: 10.0 # [m]

# params for filtering objects that are in intersection
intersection:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ struct AvoidanceParameters
bool enable_cancel_maneuver{false};

// enable avoidance for all parking vehicle
bool enable_avoidance_for_ambiguous_vehicle{false};
std::string policy_ambiguous_vehicle{"ignore"};

// enable yield maneuver.
bool enable_yield_maneuver{false};
Expand Down Expand Up @@ -192,7 +192,8 @@ struct AvoidanceParameters
double object_check_min_road_shoulder_width{0.0};

// force avoidance
double closest_distance_to_wait_and_see_for_ambiguous_vehicle{0.0};
std::vector<std::string> wait_and_see_target_behaviors{"NONE", "MERGING", "DEVIATING"};
double wait_and_see_th_closest_distance{0.0};
double time_threshold_for_ambiguous_vehicle{0.0};
double distance_threshold_for_ambiguous_vehicle{0.0};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <algorithm>
#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -325,10 +326,27 @@

const auto object = objects.front();

// if the object is NOT ambiguous, this module doesn't wait operator approval if RTC is running
// as AUTO mode.
if (!object.is_ambiguous) {
return true;
}

// check only front objects.
if (object.longitudinal < 0.0) {
return true;
}

// if the policy is "manual", this module generates candidate path and waits approval.
if (parameters_->policy_ambiguous_vehicle == "manual") {
return false;
}

// don't delay avoidance start position if it's not MERGING or DEVIATING vehicle.
if (!isWaitAndSeeTarget(object)) {
return true;
}

if (!object.avoid_margin.has_value()) {
return true;
}
Expand All @@ -341,9 +359,32 @@
const auto constant_distance = getFrontConstantDistance(object);
const auto avoidance_distance = getMinAvoidanceDistance(desire_shift_length);

return object.longitudinal <
prepare_distance + constant_distance + avoidance_distance +
parameters_->closest_distance_to_wait_and_see_for_ambiguous_vehicle;
return object.longitudinal < prepare_distance + constant_distance + avoidance_distance +
parameters_->wait_and_see_th_closest_distance;

Check warning on line 363 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp#L362-L363

Added lines #L362 - L363 were not covered by tests
}

bool isWaitAndSeeTarget(const ObjectData & object) const
{
const auto & behaviors = parameters_->wait_and_see_target_behaviors;
if (object.behavior == ObjectData::Behavior::MERGING) {
return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) {
return behavior == "MERGING";
});

Check warning on line 372 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp#L372

Added line #L372 was not covered by tests
}

if (object.behavior == ObjectData::Behavior::DEVIATING) {
return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) {
return behavior == "DEVIATING";
});

Check warning on line 378 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp#L378

Added line #L378 was not covered by tests
}

if (object.behavior == ObjectData::Behavior::NONE) {
return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) {
return behavior == "NONE";
});

Check warning on line 384 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp#L384

Added line #L384 was not covered by tests
}

return false;
}

static bool isAbsolutelyNotAvoidable(const ObjectData & object)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,9 +137,11 @@ AvoidanceParameters getParameter(rclcpp::Node * node)

{
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter<bool>(*node, ns + "enable");
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "closest_distance_to_wait_and_see");
p.policy_ambiguous_vehicle = getOrDeclareParameter<std::string>(*node, ns + "policy");
p.wait_and_see_target_behaviors =
getOrDeclareParameter<std::vector<std::string>>(*node, ns + "wait_and_see.target_behaviors");
p.wait_and_see_th_closest_distance =
getOrDeclareParameter<double>(*node, ns + "wait_and_see.th_closest_distance");
p.time_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.th_stopped_time");
p.distance_threshold_for_ambiguous_vehicle =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -716,9 +716,10 @@
"avoidance_for_ambiguous_vehicle": {
"type": "object",
"properties": {
"enable": {
"type": "boolean",
"description": "Enable avoidance maneuver for ambiguous vehicles.",
"policy": {
"type": "string",
"enum": ["auto", "manual", "ignore"],
"description": "Ego behavior policy for ambiguous vehicle.",
"default": "true"
},
"closest_distance_to_wait_and_see": {
Expand Down Expand Up @@ -778,14 +779,26 @@
},
"required": ["traffic_light", "crosswalk"],
"additionalProperties": false
},
"wait_and_see": {
"type": "object",
"properties": {
"target_behaviors": {
"type": "array",
"default": ["MERGING", "DEVIATING"],
"description": "This module doesn't avoid these behaviors vehicle until it gets closer than threshold."
},
"th_closest_distance": {
"type": "number",
"default": 10.0,
"description": "Threshold to check whether the ego gets close enough the ambiguous vehicle."
}
},
"required": ["target_behaviors", "th_closest_distance"],
"additionalProperties": false
}
},
"required": [
"enable",
"closest_distance_to_wait_and_see",
"condition",
"ignore_area"
],
"required": ["policy", "condition", "ignore_area", "wait_and_see"],
"additionalProperties": false
},
"intersection": {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,10 +132,9 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams(

{
const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle.";
updateParam<bool>(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle);
updateParam<std::string>(parameters, ns + "policy", p->policy_ambiguous_vehicle);
updateParam<double>(
parameters, ns + "closest_distance_to_wait_and_see",
p->closest_distance_to_wait_and_see_for_ambiguous_vehicle);
parameters, ns + "wait_and_see.th_closest_distance", p->wait_and_see_th_closest_distance);
updateParam<double>(
parameters, ns + "condition.th_stopped_time", p->time_threshold_for_ambiguous_vehicle);
updateParam<double>(
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_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1959 to 1950, 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_planner/autoware_behavior_path_static_obstacle_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.56 to 5.51, 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 @@ -880,15 +880,16 @@

// from here, filtering for ambiguous vehicle.

if (!parameters->enable_avoidance_for_ambiguous_vehicle) {
if (parameters->policy_ambiguous_vehicle == "ignore") {
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
return false;
}

const auto stop_time_longer_than_threshold =
object.stop_time > parameters->time_threshold_for_ambiguous_vehicle;
if (!stop_time_longer_than_threshold) {
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
object.is_ambiguous = false;

Check warning on line 892 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp#L892

Added line #L892 was not covered by tests
return false;
}

Expand All @@ -897,6 +898,7 @@
parameters->distance_threshold_for_ambiguous_vehicle;
if (is_moving_distance_longer_than_threshold) {
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
object.is_ambiguous = false;

Check warning on line 901 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp#L901

Added line #L901 was not covered by tests
return false;
}

Expand All @@ -907,22 +909,9 @@
return true;
}
} else {
if (object.behavior == ObjectData::Behavior::MERGING) {
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
object.is_ambiguous = true;
return true;
}

if (object.behavior == ObjectData::Behavior::DEVIATING) {
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
object.is_ambiguous = true;
return true;
}

if (object.behavior == ObjectData::Behavior::NONE) {
object.is_ambiguous = false;
return true;
}
object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE;
object.is_ambiguous = true;
return true;

Check notice on line 914 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

isSatisfiedWithVehicleCondition is no longer above the threshold for cyclomatic complexity. 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 914 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

isSatisfiedWithVehicleCondition is no longer above the threshold for logical blocks with deeply nested code. 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.

Check warning on line 914 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp#L912-L914

Added lines #L912 - L914 were not covered by tests
}

object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
Expand Down
Loading