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): wait and see ambiguous stopped vehicle #6631

Merged
merged 7 commits into from
Mar 18, 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 @@ -133,10 +133,13 @@

{
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<bool>(*node, ns + "enable");
p.threshold_time_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<double>(*node, ns + "time_threshold");
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.time_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.time_threshold");
p.distance_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.distance_threshold");

Check warning on line 142 in planning/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 125 to 128 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.object_ignore_section_traffic_light_in_front_distance =
getOrDeclareParameter<double>(*node, ns + "ignore_area.traffic_light.front_distance");
p.object_ignore_section_crosswalk_in_front_distance =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,8 +155,10 @@
# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
avoidance_for_ambiguous_vehicle:
enable: false # [-]
time_threshold: 1.0 # [s]
distance_threshold: 1.0 # [m]
closest_distance_to_wait_and_see: 10.0 # [m]
condition:
time_threshold: 1.0 # [s]
distance_threshold: 1.0 # [m]
ignore_area:
traffic_light:
front_distance: 100.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ struct AvoidanceParameters
bool enable_cancel_maneuver{false};

// enable avoidance for all parking vehicle
bool enable_force_avoidance_for_stopped_vehicle{false};
bool enable_avoidance_for_ambiguous_vehicle{false};

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

// force avoidance
double threshold_time_force_avoidance_for_stopped_vehicle{0.0};
double force_avoidance_distance_threshold{0.0};
double closest_distance_to_wait_and_see_for_ambiguous_vehicle{0.0};
double time_threshold_for_ambiguous_vehicle{0.0};
double distance_threshold_for_ambiguous_vehicle{0.0};

// when complete avoidance motion, there is a distance margin with the object
// for longitudinal direction
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,35 @@
});
}

bool isReady(const ObjectDataArray & objects) const
{
if (objects.empty()) {
return true;
}

const auto object = objects.front();

Check warning on line 298 in planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp#L298

Added line #L298 was not covered by tests

if (!object.is_ambiguous) {
return true;
}

if (!object.avoid_margin.has_value()) {
return true;
}

const auto is_object_on_right = utils::avoidance::isOnRight(object);
const auto desire_shift_length =
getShiftLength(object, is_object_on_right, object.avoid_margin.value());

const auto prepare_distance = getMinimumPrepareDistance();
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;
}

Check warning on line 319 in planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp#L316-L319

Added lines #L316 - L319 were not covered by tests

bool isReady(const AvoidLineArray & new_shift_lines, const double current_shift_length) const
{
if (std::abs(current_shift_length) < 1e-3) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,12 +141,13 @@ AvoidanceParameters getParameter(rclcpp::Node * node)

{
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<bool>(*node, ns + "enable");
p.threshold_time_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<double>(*node, ns + "time_threshold");
p.force_avoidance_distance_threshold =
getOrDeclareParameter<double>(*node, ns + "distance_threshold");
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.time_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.time_threshold");
p.distance_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.distance_threshold");
p.object_ignore_section_traffic_light_in_front_distance =
getOrDeclareParameter<double>(*node, ns + "ignore_area.traffic_light.front_distance");
p.object_ignore_section_crosswalk_in_front_distance =
Expand Down
2 changes: 2 additions & 0 deletions planning/behavior_path_avoidance_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -579,6 +579,8 @@
addObjects(data.other_objects, std::string("ParallelToEgoLane"));
addObjects(data.other_objects, std::string("MergingToEgoLane"));
addObjects(data.other_objects, std::string("UnstableObject"));
addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle"));
addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle(wait-and-see)"));

Check warning on line 583 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 110 to 112 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
3 changes: 2 additions & 1 deletion planning/behavior_path_avoidance_module/src/scene.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/scene.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 1185 to 1186, 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/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.93 to 4.95, 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 @@ -522,7 +522,8 @@
*/
data.comfortable = helper_->isComfortable(data.new_shift_line);
data.safe = isSafePath(data.candidate_path, debug);
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength());
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength()) &&
helper_->isReady(data.target_objects);
}

void AvoidanceModule::fillEgoStatus(
Expand Down
198 changes: 131 additions & 67 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 1901 to 1960, 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 worse: Number of Functions in a Single Module

The number of functions increases from 80 to 82, threshold = 75. This file contains too many functions. Beyond a certain threshold, more functions lower 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 worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.94 to 5.00, 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 @@ -525,7 +525,8 @@
}

bool isParkedVehicle(
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<RouteHandler> & route_handler,

Check warning on line 529 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#L529

Added line #L529 was not covered by tests
const std::shared_ptr<AvoidanceParameters> & parameters)
{
using lanelet::geometry::distance2d;
Expand Down Expand Up @@ -622,57 +623,36 @@
object.shiftable_ratio > parameters->object_check_shiftable_ratio;
}

return is_left_side_parked_vehicle || is_right_side_parked_vehicle;
}

bool isAmbiguousStoppedVehicle(
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
const auto stop_time_longer_than_threshold =
object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle;

if (!stop_time_longer_than_threshold) {
if (!is_left_side_parked_vehicle && !is_right_side_parked_vehicle) {

Check warning on line 626 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#L626

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

const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
const auto is_moving_distance_longer_than_threshold =
tier4_autoware_utils::calcDistance2d(object.init_pose, object_pose) >
parameters->force_avoidance_distance_threshold;

if (is_moving_distance_longer_than_threshold) {
return false;
}

if (object.is_within_intersection) {
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is in the intersection area.");
return false;
}

const auto rh = planner_data->route_handler;

if (
!!rh->getRoutingGraphPtr()->right(object.overhang_lanelet) &&
!!rh->getRoutingGraphPtr()->left(object.overhang_lanelet)) {
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane.");
object.to_centerline =
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {

Check warning on line 633 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#L633

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

if (!object.is_on_ego_lane) {
return true;
}
return true;
}

Check warning on line 638 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

isParkedVehicle increases in cyclomatic complexity from 11 to 13, 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.

bool isCloseToStopFactor(

Check warning on line 640 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#L640

Added line #L640 was not covered by tests
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
const auto & rh = planner_data->route_handler;

Check warning on line 645 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#L644-L645

Added lines #L644 - L645 were not covered by tests
const auto & ego_pose = planner_data->self_odometry->pose.pose;
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;

// force avoidance for stopped vehicle
bool not_parked_object = true;
bool is_close_to_stop_factor = false;

// check traffic light
const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, data.extend_lanelets);
{
not_parked_object =
is_close_to_stop_factor =
to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance;
}

Expand All @@ -684,12 +664,89 @@
const auto stop_for_crosswalk =
to_crosswalk < parameters->object_ignore_section_crosswalk_in_front_distance &&
to_crosswalk > -1.0 * parameters->object_ignore_section_crosswalk_behind_distance;
not_parked_object = not_parked_object || stop_for_crosswalk;
is_close_to_stop_factor = is_close_to_stop_factor || stop_for_crosswalk;
}

object.to_stop_factor_distance = std::min(to_traffic_light, to_crosswalk);

return !not_parked_object;
return is_close_to_stop_factor;
}

bool isNeverAvoidanceTarget(
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)

Check warning on line 678 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#L677-L678

Added lines #L677 - L678 were not covered by tests
{
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
const auto is_moving_distance_longer_than_threshold =
tier4_autoware_utils::calcDistance2d(object.init_pose, object_pose) >
parameters->distance_threshold_for_ambiguous_vehicle;
if (is_moving_distance_longer_than_threshold) {
object.reason = AvoidanceDebugFactor::MOVING_OBJECT;

Check warning on line 685 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#L685

Added line #L685 was not covered by tests
return true;
}

if (object.is_within_intersection) {
if (object.behavior == ObjectData::Behavior::NONE) {
object.reason = "ParallelToEgoLane";
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");
return true;

Check warning on line 693 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#L692-L693

Added lines #L692 - L693 were not covered by tests
}

if (object.behavior == ObjectData::Behavior::MERGING) {
object.reason = "MergingToEgoLane";
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");

Check warning on line 698 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#L697-L698

Added lines #L697 - L698 were not covered by tests
return true;
}
}

Check warning on line 702 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#L701-L702

Added lines #L701 - L702 were not covered by tests
if (object.is_on_ego_lane) {
if (
planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() &&
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it.");

Check warning on line 708 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#L708

Added line #L708 was not covered by tests
return true;
}
}

if (isCloseToStopFactor(object, data, planner_data, parameters)) {
if (object.is_on_ego_lane && !object.is_parked) {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is close to stop factor. never avoid it.");
return true;
}
}

Check warning on line 719 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#L719

Added line #L719 was not covered by tests

return false;
}

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

isNeverAvoidanceTarget has a cyclomatic complexity of 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.

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Bumpy Road Ahead

isNeverAvoidanceTarget has 3 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested 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.

bool isObviousAvoidanceTarget(
ObjectData & object, [[maybe_unused]] const AvoidancePlanningData & data,

Check warning on line 725 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#L724-L725

Added lines #L724 - L725 were not covered by tests
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data,
[[maybe_unused]] const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (!object.is_within_intersection) {
if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) {
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is obvious parked vehicle.");
return true;
}

if (!object.is_on_ego_lane && object.behavior == ObjectData::Behavior::NONE) {
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is adjacent vehicle.");
return true;
}
}

Check warning on line 739 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#L738-L739

Added lines #L738 - L739 were not covered by tests

if (!object.is_parked) {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
}

Check warning on line 743 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#L743

Added line #L743 was not covered by tests

if (object.behavior == ObjectData::Behavior::MERGING) {
object.reason = "MergingToEgoLane";

Check warning on line 746 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#L745-L746

Added lines #L745 - L746 were not covered by tests
}

return false;

Check notice on line 749 in planning/behavior_path_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

isAmbiguousStoppedVehicle 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.
}

bool isSatisfiedWithCommonCondition(
Expand Down Expand Up @@ -792,50 +849,56 @@
{
object.behavior = getObjectBehavior(object, parameters);
object.is_on_ego_lane = isOnEgoLane(object);
object.is_ambiguous = isAmbiguousStoppedVehicle(object, data, planner_data, parameters);

// from here condition check for vehicle type objects.
if (object.is_ambiguous && parameters->enable_force_avoidance_for_stopped_vehicle) {
if (isNeverAvoidanceTarget(object, data, planner_data, parameters)) {
return false;
}

Check warning on line 855 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#L855

Added line #L855 was not covered by tests

if (isObviousAvoidanceTarget(object, data, planner_data, parameters)) {
return true;
}

// check vehicle shift ratio
if (object.is_on_ego_lane) {
if (object.is_parked) {
return true;
} else {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
return false;
}
// from here, filtering for ambiguous vehicle.

if (!parameters->enable_avoidance_for_ambiguous_vehicle) {
object.reason = "AmbiguousStoppedVehicle";
return false;
}

// Object is on center line -> ignore.
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
object.to_centerline =
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;
const auto stop_time_longer_than_threshold =

Check warning on line 868 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#L868

Added line #L868 was not covered by tests
object.stop_time > parameters->time_threshold_for_ambiguous_vehicle;
if (!stop_time_longer_than_threshold) {

Check warning on line 870 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#L870

Added line #L870 was not covered by tests
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
return false;
}

if (object.is_within_intersection) {
std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else");
if (turn_direction == "straight") {
if (object.behavior == ObjectData::Behavior::DEVIATING) {
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
object.is_ambiguous = true;
return true;
}
} else {

Check warning on line 881 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#L881

Added line #L881 was not covered by tests
if (object.behavior == ObjectData::Behavior::MERGING) {
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
object.is_ambiguous = true;

Check warning on line 884 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#L884

Added line #L884 was not covered by tests
return true;
}

if (object.behavior == ObjectData::Behavior::NONE) {
object.reason = "ParallelToEgoLane";
return false;
if (object.behavior == ObjectData::Behavior::DEVIATING) {
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
object.is_ambiguous = true;

Check warning on line 890 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#L890

Added line #L890 was not covered by tests
return true;
}
}

if (object.behavior == ObjectData::Behavior::MERGING) {
object.reason = "MergingToEgoLane";
return false;
if (object.behavior == ObjectData::Behavior::NONE) {
object.is_ambiguous = false;
return true;
}
}

return true;
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
return false;

Check warning on line 901 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#L901

Added line #L901 was not covered by tests
}

bool isNoNeedAvoidanceBehavior(
Expand Down Expand Up @@ -1762,7 +1825,8 @@
if (filtering_utils::isVehicleTypeObject(o)) {
o.is_within_intersection =
filtering_utils::isWithinIntersection(o, planner_data->route_handler);
o.is_parked = filtering_utils::isParkedVehicle(o, planner_data->route_handler, parameters);
o.is_parked =
filtering_utils::isParkedVehicle(o, data, planner_data->route_handler, parameters);
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);

if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) {
Expand Down
Loading