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): don't slow down if avoidance is NOT definitely necessary during unsafe condition #6355

Merged
merged 3 commits into from
Mar 21, 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 @@ -6,8 +6,6 @@
resample_interval_for_output: 4.0 # [m]
# avoidance module common setting
enable_bound_clipping: false
enable_yield_maneuver: true
enable_yield_maneuver_during_shifting: false
enable_cancel_maneuver: true
disable_path_update: false

Expand Down Expand Up @@ -247,7 +245,8 @@

# For yield maneuver
yield:
yield_velocity: 2.78 # [m/s]
enable: true # [-]
enable_during_shifting: false # [-]

# For stop maneuver
stop:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,9 +216,6 @@ struct AvoidanceParameters
size_t hysteresis_factor_safe_count;
double hysteresis_factor_expand_rate{0.0};

// keep target velocity in yield maneuver
double yield_velocity{0.0};

// maximum stop distance
double stop_max_distance{0.0};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
getOrDeclareParameter<double>(*node, ns + "resample_interval_for_output");
p.enable_bound_clipping = getOrDeclareParameter<bool>(*node, ns + "enable_bound_clipping");
p.enable_cancel_maneuver = getOrDeclareParameter<bool>(*node, ns + "enable_cancel_maneuver");
p.enable_yield_maneuver = getOrDeclareParameter<bool>(*node, ns + "enable_yield_maneuver");
p.enable_yield_maneuver_during_shifting =
getOrDeclareParameter<bool>(*node, ns + "enable_yield_maneuver_during_shifting");
p.disable_path_update = getOrDeclareParameter<bool>(*node, ns + "disable_path_update");
p.publish_debug_marker = getOrDeclareParameter<bool>(*node, ns + "publish_debug_marker");
p.print_debug_info = getOrDeclareParameter<bool>(*node, ns + "print_debug_info");
Expand Down Expand Up @@ -295,7 +292,9 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
// yield
{
const std::string ns = "avoidance.yield.";
p.yield_velocity = getOrDeclareParameter<double>(*node, ns + "yield_velocity");
p.enable_yield_maneuver = getOrDeclareParameter<bool>(*node, ns + "enable");
p.enable_yield_maneuver_during_shifting =
getOrDeclareParameter<bool>(*node, ns + "enable_during_shifting");
}

// stop
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -233,13 +233,6 @@ class AvoidanceModule : public SceneModuleInterface
*/
void insertPrepareVelocity(ShiftedPath & shifted_path) const;

/**
* @brief insert decel point in output path in order to yield. the ego decelerates within
* accel/jerk constraints.
* @param target path.
*/
void insertYieldVelocity(ShiftedPath & shifted_path) const;

/**
* @brief calculate stop distance based on object's overhang.
* @param stop distance.
Expand Down
59 changes: 37 additions & 22 deletions 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 1188 to 1196, 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.95 to 5.17, 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 @@ -692,7 +692,6 @@
break;
}
case AvoidanceState::YIELD: {
insertYieldVelocity(path);
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
break;
}
Expand Down Expand Up @@ -1525,6 +1524,11 @@
{
const auto & data = avoid_data_;

// If avoidance path is NOT valid, don't insert any stop points.
if (!data.valid) {
return;
}

if (!data.stop_target_object) {
return;
}
Expand Down Expand Up @@ -1611,28 +1615,20 @@
getEgoPosition(), stop_distance - MARGIN, 0.0, shifted_path.path, stop_pose_);
}

void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const
void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const

Check warning on line 1618 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1618

Added line #L1618 was not covered by tests
{
const auto & p = parameters_;
const auto & data = avoid_data_;

if (data.target_objects.empty()) {
// If avoidance path is NOT safe, don't insert any slow down sections.
if (!data.safe && !data.stop_target_object) {
return;
}

if (helper_->isShifted()) {
// If avoidance path is NOT safe, don't insert any slow down sections.
if (!data.valid) {
return;
}

const auto decel_distance = helper_->getFeasibleDecelDistance(p->yield_velocity, false);
utils::avoidance::insertDecelPoint(
getEgoPosition(), decel_distance, p->yield_velocity, shifted_path.path, slow_pose_);
}

void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
{
const auto & data = avoid_data_;

// do nothing if there is no avoidance target.
if (data.target_objects.empty()) {
return;
Expand All @@ -1648,34 +1644,53 @@
return;
}

const auto object = data.target_objects.front();
const auto itr = std::find_if(

Check warning on line 1647 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1647

Added line #L1647 was not covered by tests
data.target_objects.begin(), data.target_objects.end(),
[](const auto & o) { return o.avoid_required; });

const auto object = [&]() -> std::optional<ObjectData> {

Check warning on line 1651 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1651

Added line #L1651 was not covered by tests
if (!data.yield_required) {
return data.target_objects.front();
}

if (itr == data.target_objects.end()) {
return std::nullopt;

Check warning on line 1657 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1657

Added line #L1657 was not covered by tests
}

return *itr;
}();

// do nothing if it can't avoid at the moment and avoidance is NOT definitely necessary.
if (!object.has_value()) {
return;
}

const auto enough_space =
object.is_avoidable || object.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
object.value().is_avoidable || object.value().reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
if (!enough_space) {
return;
}

// calculate shift length for front object.
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_type = utils::getHighestProbLabel(object.value().object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor +
const auto avoid_margin = object_parameter.lateral_hard_margin * object.value().distance_factor +

Check warning on line 1678 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1678

Added line #L1678 was not covered by tests
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
const auto shift_length =
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin);
const auto shift_length = helper_->getShiftLength(
object.value(), utils::avoidance::isOnRight(object.value()), avoid_margin);

// check slow down feasibility
const auto min_avoid_distance = helper_->getMinAvoidanceDistance(shift_length);
const auto distance_to_object = object.longitudinal;
const auto distance_to_object = object.value().longitudinal;

Check warning on line 1685 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L1685

Added line #L1685 was not covered by tests
const auto remaining_distance = distance_to_object - min_avoid_distance;
const auto decel_distance = helper_->getFeasibleDecelDistance(parameters_->velocity_map.front());
if (remaining_distance < decel_distance) {
return;
}

// decide slow down lower limit.
const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed;
const auto lower_speed = object.value().avoid_required ? 0.0 : parameters_->min_slow_down_speed;

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

AvoidanceModule::insertPrepareVelocity increases in cyclomatic complexity from 11 to 17, 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.

// insert slow down speed.
const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk(
Expand Down
Loading