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): configurable object type for safety check #5699

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 @@ -27,7 +27,6 @@
# avoidance is performed for the object type with true
target_object:
car:
is_target: true # [-]
execute_num: 1 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 1.0 # [s]
Expand All @@ -38,7 +37,6 @@
safety_buffer_longitudinal: 0.0 # [m]
use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
truck:
is_target: true
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -49,7 +47,6 @@
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
bus:
is_target: true
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -60,7 +57,6 @@
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
trailer:
is_target: true
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -71,7 +67,6 @@
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
unknown:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -82,7 +77,6 @@
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
bicycle:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -93,7 +87,6 @@
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
motorcycle:
is_target: true
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -104,7 +97,6 @@
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
pedestrian:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -119,6 +111,16 @@

# For target object filtering
target_filtering:
# avoidance target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: true # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# detection range
object_check_goal_distance: 20.0 # [m]
# filtering parking objects
Expand Down Expand Up @@ -152,6 +154,16 @@

# For safety check
safety_check:
# safety check target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: false # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# safety check configuration
enable: true # [-]
check_current_lane: false # [-]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
# avoidance is performed for the object type with true
target_object:
car:
is_target: true # [-]
execute_num: 2 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 1.0 # [s]
Expand All @@ -16,7 +15,6 @@
avoid_margin_lateral: 1.0 # [m]
safety_buffer_lateral: 0.7 # [m]
truck:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -25,7 +23,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
bus:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -34,7 +31,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
trailer:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -43,7 +39,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
unknown:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -52,7 +47,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.0
bicycle:
is_target: true
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -61,7 +55,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
motorcycle:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -70,7 +63,6 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
pedestrian:
is_target: true
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -80,3 +72,16 @@
safety_buffer_lateral: 1.0
lower_distance_for_polygon_expansion: 0.0 # [m]
upper_distance_for_polygon_expansion: 1.0 # [m]

# For target object filtering
target_filtering:
# avoidance target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: true # [-]
bicycle: false # [-]
motorcycle: false # [-]
pedestrian: false # [-]
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,9 @@ using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug;

struct ObjectParameter
{
bool is_target{false};
bool is_avoidance_target{false};

bool is_safety_check_target{false};

size_t execute_num{1};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,90 +64,123 @@
// target object
{
const auto get_object_param = [&](std::string && ns) {
ObjectParameter param{};
param.is_target = getOrDeclareParameter<bool>(*node, ns + "is_target");
param.execute_num = getOrDeclareParameter<int>(*node, ns + "execute_num");
param.moving_speed_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_speed_threshold");
param.moving_time_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_time_threshold");
param.max_expand_ratio = getOrDeclareParameter<double>(*node, ns + "max_expand_ratio");
param.envelope_buffer_margin =
getOrDeclareParameter<double>(*node, ns + "envelope_buffer_margin");
param.avoid_margin_lateral =
getOrDeclareParameter<double>(*node, ns + "avoid_margin_lateral");
param.safety_buffer_lateral =
getOrDeclareParameter<double>(*node, ns + "safety_buffer_lateral");
param.safety_buffer_longitudinal =
getOrDeclareParameter<double>(*node, ns + "safety_buffer_longitudinal");
param.use_conservative_buffer_longitudinal =
getOrDeclareParameter<bool>(*node, ns + "use_conservative_buffer_longitudinal");
return param;
};

const std::string ns = "avoidance.target_object.";
p.object_parameters.emplace(
ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle."));
p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car."));
p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck."));
p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer."));
p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus."));
p.object_parameters.emplace(
ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian."));
p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle."));
p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown."));

p.lower_distance_for_polygon_expansion =
getOrDeclareParameter<double>(*node, ns + "lower_distance_for_polygon_expansion");
p.upper_distance_for_polygon_expansion =
getOrDeclareParameter<double>(*node, ns + "upper_distance_for_polygon_expansion");
}

// target filtering
{
const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) {
if (p.object_parameters.count(object_type) == 0) {
return;
}
p.object_parameters.at(object_type).is_avoidance_target =
getOrDeclareParameter<bool>(*node, ns);
};

std::string ns = "avoidance.target_filtering.";
set_target_flag(ObjectClassification::CAR, ns + "target_type.car");
set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck");
set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer");
set_target_flag(ObjectClassification::BUS, ns + "target_type.bus");
set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian");
set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle");
set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle");
set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown");

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_check_yaw_deviation =
getOrDeclareParameter<double>(*node, ns + "intersection.yaw_deviation");
p.object_last_seen_threshold =
getOrDeclareParameter<double>(*node, ns + "object_last_seen_threshold");
}

{
std::string ns = "avoidance.target_filtering.force_avoidance.";
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.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 =
getOrDeclareParameter<double>(*node, ns + "ignore_area.crosswalk.front_distance");
p.object_ignore_section_crosswalk_behind_distance =
getOrDeclareParameter<double>(*node, ns + "ignore_area.crosswalk.behind_distance");
}

{
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");
}

// safety check general params
{
const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) {
if (p.object_parameters.count(object_type) == 0) {
return;
}
p.object_parameters.at(object_type).is_safety_check_target =
getOrDeclareParameter<bool>(*node, ns);
};

std::string ns = "avoidance.safety_check.";
set_target_flag(ObjectClassification::CAR, ns + "target_type.car");
set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck");
set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer");
set_target_flag(ObjectClassification::BUS, ns + "target_type.bus");
set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian");
set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle");
set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle");
set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown");

Check warning on line 183 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 increases in cyclomatic complexity from 16 to 18, 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.
p.enable_safety_check = getOrDeclareParameter<bool>(*node, ns + "enable");
p.check_current_lane = getOrDeclareParameter<bool>(*node, ns + "check_current_lane");
p.check_shift_side_lane = getOrDeclareParameter<bool>(*node, ns + "check_shift_side_lane");
Expand Down Expand Up @@ -346,7 +379,6 @@
const auto update_object_param = [&p, &parameters](
const auto & semantic, const std::string & ns) {
auto & config = p->object_parameters.at(semantic);
updateParam<bool>(parameters, ns + "is_target", config.is_target);
updateParam<double>(parameters, ns + "moving_speed_threshold", config.moving_speed_threshold);
updateParam<double>(parameters, ns + "moving_time_threshold", config.moving_time_threshold);
updateParam<double>(parameters, ns + "max_expand_ratio", config.max_expand_ratio);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -284,44 +284,60 @@
// target object
{
const auto get_object_param = [&](std::string && ns) {
ObjectParameter param{};
param.is_target = getOrDeclareParameter<bool>(*node, ns + "is_target");
param.execute_num = getOrDeclareParameter<int>(*node, ns + "execute_num");
param.moving_speed_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_speed_threshold");
param.moving_time_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_time_threshold");
param.max_expand_ratio = getOrDeclareParameter<double>(*node, ns + "max_expand_ratio");
param.envelope_buffer_margin =
getOrDeclareParameter<double>(*node, ns + "envelope_buffer_margin");
param.avoid_margin_lateral =
getOrDeclareParameter<double>(*node, ns + "avoid_margin_lateral");
param.safety_buffer_lateral =
getOrDeclareParameter<double>(*node, ns + "safety_buffer_lateral");
return param;
};

const std::string ns = "avoidance_by_lane_change.target_object.";
p.object_parameters.emplace(
ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle."));
p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car."));
p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck."));
p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer."));
p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus."));
p.object_parameters.emplace(
ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian."));
p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle."));
p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown."));

p.lower_distance_for_polygon_expansion =
getOrDeclareParameter<double>(*node, ns + "lower_distance_for_polygon_expansion");
p.upper_distance_for_polygon_expansion =
getOrDeclareParameter<double>(*node, ns + "upper_distance_for_polygon_expansion");
}

// target filtering
{
const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) {
if (p.object_parameters.count(object_type) == 0) {
return;
}
p.object_parameters.at(object_type).is_avoidance_target =
getOrDeclareParameter<bool>(*node, ns);
};

std::string ns = "avoidance.target_filtering.";
set_target_flag(ObjectClassification::CAR, ns + "target_type.car");
set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck");
set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer");
set_target_flag(ObjectClassification::BUS, ns + "target_type.bus");
set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian");
set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle");
set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle");
set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown");

Check warning on line 340 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 107 to 121 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_check_goal_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_goal_distance");
p.threshold_distance_object_is_on_center =
Expand Down
26 changes: 20 additions & 6 deletions planning/behavior_path_planner/src/utils/avoidance/utils.cpp
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/utils/avoidance/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 1551 to 1562, 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/src/utils/avoidance/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 4.70 to 4.68, 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 @@ -235,7 +235,7 @@

namespace filtering_utils
{
bool isTargetObjectType(
bool isAvoidanceTargetObjectType(

Check warning on line 238 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L238

Added line #L238 was not covered by tests
const PredictedObject & object, const std::shared_ptr<AvoidanceParameters> & parameters)
{
const auto object_type = utils::getHighestProbLabel(object.classification);
Expand All @@ -244,7 +244,19 @@
return false;
}

return parameters->object_parameters.at(object_type).is_target;
return parameters->object_parameters.at(object_type).is_avoidance_target;

Check warning on line 247 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L247

Added line #L247 was not covered by tests
}

bool isSafetyCheckTargetObjectType(

Check warning on line 250 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L250

Added line #L250 was not covered by tests
const PredictedObject & object, const std::shared_ptr<AvoidanceParameters> & parameters)
{
const auto object_type = utils::getHighestProbLabel(object.classification);

if (parameters->object_parameters.count(object_type) == 0) {
return false;
}

return parameters->object_parameters.at(object_type).is_safety_check_target;

Check warning on line 259 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L259

Added line #L259 was not covered by tests
}

bool isVehicleTypeObject(const ObjectData & object)
Expand Down Expand Up @@ -311,17 +323,17 @@
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
}

bool isParallelToEgoLane(const ObjectData & object, const double threshold)

Check warning on line 326 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L326

Added line #L326 was not covered by tests
{
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;

Check warning on line 328 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L328

Added line #L328 was not covered by tests
const auto closest_pose =
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position);
const auto yaw_deviation = std::abs(calcYawDeviation(closest_pose, object_pose));

Check warning on line 331 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L330-L331

Added lines #L330 - L331 were not covered by tests

return yaw_deviation < threshold || yaw_deviation > M_PI - threshold;
}

bool isObjectOnRoadShoulder(

Check warning on line 336 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L336

Added line #L336 was not covered by tests
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
Expand All @@ -334,7 +346,7 @@
// assume that there are no parked vehicles in intersection.
std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else");
if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") {
return false;

Check warning on line 349 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L349

Added line #L349 was not covered by tests
}

// ============================================ <- most_left_lanelet.leftBound()
Expand All @@ -357,7 +369,7 @@

bool is_left_side_parked_vehicle = false;
if (!isOnRight(object)) {
auto [object_shiftable_distance, sub_type] = [&]() {

Check warning on line 372 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L372

Added line #L372 was not covered by tests
const auto most_left_road_lanelet =
route_handler->getMostLeftLanelet(object.overhang_lanelet);
const auto most_left_lanelet_candidates =
Expand All @@ -373,7 +385,7 @@
if (sub_type.value() == "road_shoulder") {
most_left_lanelet = ll;
}
}

Check warning on line 388 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L388

Added line #L388 was not covered by tests

const auto center_to_left_boundary =
distance2d(to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point));
Expand All @@ -383,19 +395,19 @@
}();

if (sub_type.value() != "road_shoulder") {
object_shiftable_distance += parameters->object_check_min_road_shoulder_width;

Check warning on line 398 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L398

Added line #L398 was not covered by tests
}

const auto arc_coordinates = toArcCoordinates(
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance;

Check warning on line 403 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L403

Added line #L403 was not covered by tests

is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio;

Check warning on line 405 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L405

Added line #L405 was not covered by tests
}

bool is_right_side_parked_vehicle = false;
if (isOnRight(object)) {
auto [object_shiftable_distance, sub_type] = [&]() {

Check warning on line 410 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L410

Added line #L410 was not covered by tests
const auto most_right_road_lanelet =
route_handler->getMostRightLanelet(object.overhang_lanelet);
const auto most_right_lanelet_candidates =
Expand All @@ -411,7 +423,7 @@
if (sub_type.value() == "road_shoulder") {
most_right_lanelet = ll;
}
}

Check warning on line 426 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L426

Added line #L426 was not covered by tests

const auto center_to_right_boundary =
distance2d(to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point));
Expand All @@ -421,18 +433,18 @@
}();

if (sub_type.value() != "road_shoulder") {
object_shiftable_distance += parameters->object_check_min_road_shoulder_width;

Check warning on line 436 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L436

Added line #L436 was not covered by tests
}

const auto arc_coordinates = toArcCoordinates(
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance;

Check warning on line 441 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L441

Added line #L441 was not covered by tests

is_right_side_parked_vehicle =
object.shiftable_ratio > parameters->object_check_shiftable_ratio;

Check warning on line 444 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L443-L444

Added lines #L443 - L444 were not covered by tests
}

return is_left_side_parked_vehicle || is_right_side_parked_vehicle;

Check warning on line 447 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L447

Added line #L447 was not covered by tests
}

bool isForceAvoidanceTarget(
Expand Down Expand Up @@ -494,87 +506,87 @@
return !not_parked_object;
}

bool isSatisfiedWithCommonCondition(

Check warning on line 509 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L509

Added line #L509 was not covered by tests
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
// Step1. filtered by target object type.
if (!isTargetObjectType(object.object, parameters)) {
if (!isAvoidanceTargetObjectType(object.object, parameters)) {
object.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE;
return false;

Check warning on line 517 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L516-L517

Added lines #L516 - L517 were not covered by tests
}

// Step2. filtered stopped objects.
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters->object_parameters.at(object_type);

Check warning on line 522 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L521-L522

Added lines #L521 - L522 were not covered by tests
if (object.move_time > object_parameter.moving_time_threshold) {
object.reason = AvoidanceDebugFactor::MOVING_OBJECT;
return false;

Check warning on line 525 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L524-L525

Added lines #L524 - L525 were not covered by tests
}

// Step3. filtered by longitudinal distance.
const auto & ego_pos = planner_data->self_odometry->pose.pose.position;
fillLongitudinalAndLengthByClosestEnvelopeFootprint(data.reference_path_rough, ego_pos, object);

Check warning on line 530 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L529-L530

Added lines #L529 - L530 were not covered by tests

if (object.longitudinal < -parameters->object_check_backward_distance) {
object.reason = AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD;
return false;

Check warning on line 534 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L533-L534

Added lines #L533 - L534 were not covered by tests
}

if (object.longitudinal > parameters->object_check_max_forward_distance) {
object.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD;
return false;

Check warning on line 539 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L538-L539

Added lines #L538 - L539 were not covered by tests
}

// Step4. filtered by distance between object and goal position.
// TODO(Satoshi OTA): remove following two conditions after it can execute avoidance and goal
// planner module simultaneously.
const auto & rh = planner_data->route_handler;
const auto ego_idx = planner_data->findEgoIndex(data.reference_path_rough.points);

Check warning on line 546 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L546

Added line #L546 was not covered by tests
const auto to_goal_distance =
rh->isInGoalRouteSection(data.current_lanelets.back())

Check warning on line 548 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L548

Added line #L548 was not covered by tests
? calcSignedArcLength(
data.reference_path_rough.points, ego_idx, data.reference_path_rough.points.size() - 1)
: std::numeric_limits<double>::max();

if (object.longitudinal > to_goal_distance) {
object.reason = AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL;
return false;

Check warning on line 555 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L554-L555

Added lines #L554 - L555 were not covered by tests
}

if (
object.longitudinal + object.length / 2 + parameters->object_check_goal_distance >
to_goal_distance) {
object.reason = "TooNearToGoal";
return false;

Check warning on line 562 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L561-L562

Added lines #L561 - L562 were not covered by tests
}

return true;
}

bool isSatisfiedWithNonVehicleCondition(

Check warning on line 568 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L568

Added line #L568 was not covered by tests
ObjectData & object, [[maybe_unused]] const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
[[maybe_unused]] const std::shared_ptr<AvoidanceParameters> & parameters)
{
// avoidance module ignore pedestrian and bicycle around crosswalk
if (isWithinCrosswalk(object, planner_data->route_handler->getOverallGraphPtr())) {
object.reason = "CrosswalkUser";
return false;

Check warning on line 576 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L575-L576

Added lines #L575 - L576 were not covered by tests
}

return true;
}

bool isSatisfiedWithVehicleCondition(

Check warning on line 582 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L582

Added line #L582 was not covered by tests
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
using boost::geometry::within;

object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler);

Check warning on line 589 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L589

Added line #L589 was not covered by tests

// from here condition check for vehicle type objects.
if (isForceAvoidanceTarget(object, data, planner_data, parameters)) {
Expand All @@ -583,8 +595,8 @@

// Object is on center line -> ignore.
if (std::abs(object.lateral) < parameters->threshold_distance_object_is_on_center) {
object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
return false;

Check warning on line 599 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L598-L599

Added lines #L598 - L599 were not covered by tests
}

lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y());
Expand All @@ -594,8 +606,8 @@
if (isObjectOnRoadShoulder(object, planner_data->route_handler, parameters)) {
return true;
} else {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
return false;

Check warning on line 610 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L609-L610

Added lines #L609 - L610 were not covered by tests
}
}

Expand All @@ -604,14 +616,14 @@
}

if (isParallelToEgoLane(object, parameters->object_check_yaw_deviation)) {
object.reason = "ParallelToEgoLane";
return false;

Check warning on line 620 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L619-L620

Added lines #L619 - L620 were not covered by tests
}

return true;
}

bool isNoNeedAvoidanceBehavior(

Check warning on line 626 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L626

Added line #L626 was not covered by tests
ObjectData & object, const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (!object.avoid_margin.has_value()) {
Expand All @@ -619,48 +631,48 @@
}

const auto shift_length =
calcShiftLength(isOnRight(object), object.overhang_dist, object.avoid_margin.value());

Check warning on line 634 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L634

Added line #L634 was not covered by tests
if (!isShiftNecessary(isOnRight(object), shift_length)) {
object.reason = "NotNeedAvoidance";
return true;

Check warning on line 637 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L636-L637

Added lines #L636 - L637 were not covered by tests
}

if (std::abs(shift_length) < parameters->lateral_execution_threshold) {
object.reason = "LessThanExecutionThreshold";
return true;

Check warning on line 642 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L641-L642

Added lines #L641 - L642 were not covered by tests
}

return false;
}

std::optional<double> getAvoidMargin(

Check warning on line 648 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L648

Added line #L648 was not covered by tests
const ObjectData & object, const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
const auto & vehicle_width = planner_data->parameters.vehicle_width;
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters->object_parameters.at(object_type);

Check warning on line 654 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L653-L654

Added lines #L653 - L654 were not covered by tests

const auto max_avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor +
object_parameter.avoid_margin_lateral + 0.5 * vehicle_width;
const auto min_avoid_margin = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width;

Check warning on line 658 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L656-L658

Added lines #L656 - L658 were not covered by tests
const auto soft_lateral_distance_limit =
object.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width;
const auto hard_lateral_distance_limit =
object.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width;

Check warning on line 662 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L662

Added line #L662 was not covered by tests

// Step1. check avoidable or not.
if (hard_lateral_distance_limit < min_avoid_margin) {
return std::nullopt;

Check warning on line 666 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L666

Added line #L666 was not covered by tests
}

// Step2. check if it should expand road shoulder margin.
if (soft_lateral_distance_limit < min_avoid_margin) {
return min_avoid_margin;

Check warning on line 671 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L671

Added line #L671 was not covered by tests
}

// Step3. nominal case. avoid margin is limited by soft constraint.
return std::min(soft_lateral_distance_limit, max_avoid_margin);

Check warning on line 675 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L675

Added line #L675 was not covered by tests
}
} // namespace filtering_utils

Expand Down Expand Up @@ -741,20 +753,20 @@
return path_arclength_arr.size() - 1;
}

std::vector<UUID> concatParentIds(const std::vector<UUID> & ids1, const std::vector<UUID> & ids2)

Check warning on line 756 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L756

Added line #L756 was not covered by tests
{
std::vector<UUID> ret;
for (const auto id2 : ids2) {
if (std::any_of(ids1.begin(), ids1.end(), [&id2](const auto & id1) { return id1 == id2; })) {
continue;

Check warning on line 761 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L761

Added line #L761 was not covered by tests
}
ret.push_back(id2);
}

return ret;

Check warning on line 766 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L766

Added line #L766 was not covered by tests
}

std::vector<UUID> calcParentIds(const AvoidLineArray & lines1, const AvoidLine & lines2)

Check warning on line 769 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L769

Added line #L769 was not covered by tests
{
// Get the ID of the original AP whose transition area overlaps with the given AP,
// and set it to the parent id.
Expand All @@ -770,7 +782,7 @@

ret.push_back(al.id);
}
return ret;

Check warning on line 785 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L785

Added line #L785 was not covered by tests
}

double lerpShiftLengthOnArc(double arc, const AvoidLine & ap)
Expand Down Expand Up @@ -935,7 +947,7 @@

// generate obstacle polygon
const double diff_poly_buffer =
object.avoid_margin.value() - object_parameter.envelope_buffer_margin - vehicle_width / 2.0;

Check warning on line 950 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L950

Added line #L950 was not covered by tests
const auto obj_poly =
tier4_autoware_utils::expandPolygon(object.envelope_poly, diff_poly_buffer);
const bool is_left = 0 < object.lateral;
Expand Down Expand Up @@ -1031,7 +1043,7 @@
}

return extend_lanelets;
}

Check warning on line 1046 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1046

Added line #L1046 was not covered by tests

void insertDecelPoint(
const Point & p_src, const double offset, const double velocity, PathWithLaneId & path,
Expand Down Expand Up @@ -1333,7 +1345,7 @@
}
}

double getRoadShoulderDistance(

Check warning on line 1348 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1348

Added line #L1348 was not covered by tests
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
Expand All @@ -1342,16 +1354,16 @@

const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
const auto object_closest_index =
findNearestIndex(data.reference_path_rough.points, object_pose.position);

Check warning on line 1357 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1357

Added line #L1357 was not covered by tests
const auto object_closest_pose =
data.reference_path_rough.points.at(object_closest_index).point.pose;

Check warning on line 1359 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1359

Added line #L1359 was not covered by tests

const auto rh = planner_data->route_handler;
if (!rh->getClosestLaneletWithinRoute(object_closest_pose, &object.overhang_lanelet)) {
return 0.0;
}

double road_shoulder_distance = std::numeric_limits<double>::max();

Check warning on line 1366 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1366

Added line #L1366 was not covered by tests

const bool get_left = isOnRight(object) && parameters->use_adjacent_lane;
const bool get_right = !isOnRight(object) && parameters->use_adjacent_lane;
Expand All @@ -1363,16 +1375,16 @@

lanelet::ConstLineString3d target_line{};

const auto update_road_to_shoulder_distance = [&](const auto & target_lanelet) {
const auto lines =
rh->getFurthestLinestring(target_lanelet, get_right, get_left, get_opposite, true);

Check warning on line 1380 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1378-L1380

Added lines #L1378 - L1380 were not covered by tests
const auto & line = isOnRight(object) ? lines.back() : lines.front();
const auto d = boost::geometry::distance(object.envelope_poly, to2D(line.basicLineString()));
if (d < road_shoulder_distance) {
road_shoulder_distance = d;
target_line = line;

Check warning on line 1385 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1384-L1385

Added lines #L1384 - L1385 were not covered by tests
}
};

Check warning on line 1387 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1387

Added line #L1387 was not covered by tests

// current lanelet
{
Expand All @@ -1380,7 +1392,7 @@

road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon(
rh, target_line, road_shoulder_distance, object.overhang_lanelet,
object.overhang_pose.position, p_overhang, parameters->use_hatched_road_markings,

Check warning on line 1395 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1395

Added line #L1395 was not covered by tests
parameters->use_intersection_areas);
}

Expand All @@ -1389,9 +1401,9 @@
if (rh->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &previous_lanelet)) {
update_road_to_shoulder_distance(previous_lanelet.front());

road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon(

Check warning on line 1404 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1404

Added line #L1404 was not covered by tests
rh, target_line, road_shoulder_distance, previous_lanelet.front(),
object.overhang_pose.position, p_overhang, parameters->use_hatched_road_markings,

Check warning on line 1406 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1406

Added line #L1406 was not covered by tests
parameters->use_intersection_areas);
}

Expand All @@ -1400,13 +1412,13 @@
if (rh->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) {
update_road_to_shoulder_distance(next_lanelet);

road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon(

Check warning on line 1415 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1415

Added line #L1415 was not covered by tests
rh, target_line, road_shoulder_distance, next_lanelet, object.overhang_pose.position,
p_overhang, parameters->use_hatched_road_markings, parameters->use_intersection_areas);
}

return road_shoulder_distance;
}

Check warning on line 1421 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1421

Added line #L1421 was not covered by tests

void filterTargetObjects(
ObjectDataArray & objects, AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug,
Expand All @@ -1414,14 +1426,14 @@
const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (data.current_lanelets.empty()) {
return;

Check warning on line 1429 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1429

Added line #L1429 was not covered by tests
}

const rclcpp::Time now = rclcpp::Clock(RCL_ROS_TIME).now();
const auto push_target_object = [&data, &now](auto & object) {
object.last_seen = now;
data.target_objects.push_back(object);
};

Check warning on line 1436 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1436

Added line #L1436 was not covered by tests

for (auto & o : objects) {
if (!filtering_utils::isSatisfiedWithCommonCondition(o, data, planner_data, parameters)) {
Expand Down Expand Up @@ -1705,10 +1717,12 @@
});
};

const auto to_predicted_objects = [&p](const auto & objects) {
const auto to_predicted_objects = [&p, &parameters](const auto & objects) {

Check warning on line 1720 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1720

Added line #L1720 was not covered by tests
PredictedObjects ret{};
std::for_each(objects.begin(), objects.end(), [&p, &ret](const auto & object) {
ret.objects.push_back(object.object);
std::for_each(objects.begin(), objects.end(), [&p, &ret, &parameters](const auto & object) {

Check warning on line 1722 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1722

Added line #L1722 was not covered by tests
if (filtering_utils::isSafetyCheckTargetObjectType(object.object, parameters)) {
ret.objects.push_back(object.object);

Check warning on line 1724 in planning/behavior_path_planner/src/utils/avoidance/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/utils/avoidance/utils.cpp#L1724

Added line #L1724 was not covered by tests
}

Check warning on line 1725 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: Complex Method

getSafetyCheckTargetObjects increases in cyclomatic complexity from 17 to 18, 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.
});
return ret;
};
Expand Down
Loading