Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(avoidance): fix bug in shift lon distance calculation #5557

Merged
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 @@ -185,7 +185,8 @@
max_shift_length, getLateralMinJerkLimit(), getEgoSpeed());

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

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

View check run for this annotation

Codecov / codecov/patch

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

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

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 2214 to 2216, 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/scene_module/avoidance/avoidance_module.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 6.19 to 6.21, 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 @@ -224,7 +224,7 @@

// If the vehicle is on the shift line, keep RUNNING.
{
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);

Check warning on line 227 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L227

Added line #L227 was not covered by tests
const auto within = [](const auto & line, const size_t idx) {
return line.start_idx < idx && idx < line.end_idx;
};
Expand Down Expand Up @@ -920,8 +920,9 @@
const auto & base_link2rear = planner_data_->parameters.base_link2rear;

// Calculate feasible shift length
const auto get_shift_length =
[&](auto & object, const auto & desire_shift_length) -> boost::optional<double> {
const auto get_shift_profile =
[&](

Check warning on line 924 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L924

Added line #L924 was not covered by tests
auto & object, const auto & desire_shift_length) -> std::optional<std::pair<double, double>> {
// use each object param
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
Expand All @@ -931,55 +932,57 @@
const auto avoiding_shift = desire_shift_length - current_ego_shift;
const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(avoiding_shift);

// calculate remaining distance.
const auto prepare_distance = helper_.getNominalPrepareDistance();
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal

Check warning on line 938 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L938

Added line #L938 was not covered by tests
? planner_data_->parameters.base_link2front
: 0.0;
const auto constant = object_parameter.safety_buffer_longitudinal +

Check warning on line 941 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L941

Added line #L941 was not covered by tests
additional_buffer_longitudinal + prepare_distance;
const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance;
const auto remaining_distance = object.longitudinal - constant;

Check warning on line 944 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L943-L944

Added lines #L943 - L944 were not covered by tests
const auto avoidance_distance =
has_enough_distance ? nominal_avoid_distance : remaining_distance;

// nominal case. avoidable.
if (has_enough_distance) {
return std::make_pair(desire_shift_length, avoidance_distance);
}

if (!isBestEffort(parameters_->policy_lateral_margin)) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// ego already has enough positive shift.
const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3;
if (is_object_on_right && has_enough_positive_shift) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// ego already has enough negative shift.
const auto has_enough_negative_shift = avoiding_shift > 1e-3 && desire_shift_length < -1e-3;
if (!is_object_on_right && has_enough_negative_shift) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// don't relax shift length since it can stop in front of the object.
if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// calculate remaining distance.
const auto prepare_distance = helper_.getNominalPrepareDistance();
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal
? planner_data_->parameters.base_link2front
: 0.0;
const auto constant = object_parameter.safety_buffer_longitudinal +
additional_buffer_longitudinal + prepare_distance;
const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance;
const auto remaining_distance = object.longitudinal - constant;

// the avoidance path is already approved
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
const auto is_approved = (helper_.getShift(object_pos) > 0.0 && is_object_on_right) ||
(helper_.getShift(object_pos) < 0.0 && !is_object_on_right);
if (is_approved) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// prepare distance is not enough. unavoidable.
if (remaining_distance < 1e-3) {
object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO;
return boost::none;
}

// nominal case. avoidable.
if (has_enough_distance) {
return desire_shift_length;
return std::nullopt;

Check warning on line 985 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L985

Added line #L985 was not covered by tests
}

// calculate lateral jerk.
Expand All @@ -988,13 +991,13 @@

// relax lateral jerk limit. avoidable.
if (required_jerk < helper_.getLateralMaxJerkLimit()) {
return desire_shift_length;
return std::make_pair(desire_shift_length, avoidance_distance);
}

// avoidance distance is not enough. unavoidable.
if (!isBestEffort(parameters_->policy_deceleration)) {
object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK;
return boost::none;
return std::nullopt;

Check warning on line 1000 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1000

Added line #L1000 was not covered by tests
}

// output avoidance path under lateral jerk constraints.
Expand All @@ -1003,7 +1006,7 @@

if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) {
object.reason = "LessThanExecutionThreshold";
return boost::none;
return std::nullopt;

Check warning on line 1009 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1009

Added line #L1009 was not covered by tests
}

const auto feasible_shift_length =
Expand All @@ -1016,8 +1019,8 @@
if (infeasible) {
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 1000, "feasible shift length is not enough to avoid. ");
object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK;
return boost::none;
return std::nullopt;

Check warning on line 1023 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1022-L1023

Added lines #L1022 - L1023 were not covered by tests
}

{
Expand All @@ -1026,7 +1029,7 @@
std::abs(avoiding_shift), feasible_relative_shift_length);
}

return feasible_shift_length;
return std::make_pair(feasible_shift_length, avoidance_distance);
};

const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; };
Expand Down Expand Up @@ -1061,9 +1064,9 @@
// use each object param
const auto object_type = utils::getHighestProbLabel(o.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto feasible_shift_length = get_shift_length(o, desire_shift_length);
const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length);

if (!feasible_shift_length) {
if (!feasible_shift_profile.has_value()) {
if (o.avoid_required && is_forward_object(o)) {
break;
} else {
Expand All @@ -1072,10 +1075,8 @@
}

// use absolute dist for return-to-center, relative dist from current for avoiding.
const auto feasible_avoid_distance =
helper_.getMaxAvoidanceDistance(feasible_shift_length.get() - current_ego_shift);
const auto feasible_return_distance =
helper_.getMaxAvoidanceDistance(feasible_shift_length.get());
helper_.getMaxAvoidanceDistance(feasible_shift_profile.value().first);

AvoidLine al_avoid;
{
Expand All @@ -1091,14 +1092,15 @@

// start point (use previous linear shift length as start shift length.)
al_avoid.start_longitudinal = [&]() {
const auto nearest_avoid_distance = std::max(to_shift_end - feasible_avoid_distance, 1e-3);
const auto nearest_avoid_distance =
std::max(to_shift_end - feasible_shift_profile.value().second, 1e-3);

if (data.to_start_point > to_shift_end) {
return nearest_avoid_distance;
}

const auto minimum_avoid_distance =
helper_.getMinAvoidanceDistance(feasible_shift_length.get() - current_ego_shift);
helper_.getMinAvoidanceDistance(feasible_shift_profile.value().first - current_ego_shift);

Check warning on line 1103 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1103

Added line #L1103 was not covered by tests
const auto furthest_avoid_distance = std::max(to_shift_end - minimum_avoid_distance, 1e-3);

return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance);
Expand All @@ -1110,7 +1112,7 @@
al_avoid.start_shift_length = helper_.getLinearShift(al_avoid.start.position);

// end point
al_avoid.end_shift_length = feasible_shift_length.get();
al_avoid.end_shift_length = feasible_shift_profile.value().first;

Check warning on line 1115 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1115

Added line #L1115 was not covered by tests
al_avoid.end_longitudinal = to_shift_end;

// misc
Expand All @@ -1125,7 +1127,7 @@
const auto to_shift_start = o.longitudinal + offset;

// start point
al_return.start_shift_length = feasible_shift_length.get();
al_return.start_shift_length = feasible_shift_profile.value().first;

Check warning on line 1130 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AvoidanceModule::generateAvoidOutline increases in cyclomatic complexity from 43 to 44, 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 warning on line 1130 in planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp#L1130

Added line #L1130 was not covered by tests
al_return.start_longitudinal = to_shift_start;

// end point
Expand Down
Loading