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): use traffic light signal info #5395

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 @@ -186,11 +186,18 @@
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
remain_buffer_distance: 30.0 # [m]
min_prepare_distance: 1.0 # [m]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s]
nominal_avoidance_speed: 8.33 # [m/s]
# return dead line
return_dead_line:
goal:
enable: true # [-]
buffer: 30.0 # [m]
traffic_light:
enable: true # [-]
buffer: 3.0 # [m]

# For yield maneuver
yield:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,14 @@ struct AvoidanceParameters
// use intersection area for avoidance
bool use_intersection_areas{false};

// consider avoidance return dead line
bool enable_dead_line_for_goal{false};
bool enable_dead_line_for_traffic_light{false};

// module try to return original path to keep this distance from edge point of the path.
double dead_line_buffer_for_goal{0.0};
double dead_line_buffer_for_traffic_light{0.0};

// max deceleration for
double max_deceleration{0.0};

Expand Down Expand Up @@ -217,9 +225,6 @@ struct AvoidanceParameters
// nominal avoidance sped
double nominal_avoidance_speed{0.0};

// module try to return original path to keep this distance from edge point of the path.
double remain_buffer_distance{0.0};

// The margin is configured so that the generated avoidance trajectory does not come near to the
// road shoulder.
double soft_road_shoulder_margin{1.0};
Expand Down Expand Up @@ -514,6 +519,10 @@ struct AvoidancePlanningData
bool found_avoidance_path{false};

double to_stop_line{std::numeric_limits<double>::max()};

double to_start_point{std::numeric_limits<double>::lowest()};

double to_return_point{std::numeric_limits<double>::max()};
};

/*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,16 @@ std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
DrivableLanes generateExpandDrivableLanes(
const lanelet::ConstLanelet & lanelet, const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters);

double calcDistanceToReturnDeadLine(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters);

double calcDistanceToAvoidStartLine(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters);
} // namespace behavior_path_planner::utils::avoidance

#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_
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 2175 to 2190, 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.08 to 6.11, 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 @@ -288,6 +288,12 @@
data.reference_path, 0, data.reference_path.points.size(),
calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0));

data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine(
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);

data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine(
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);

// target objects for avoidance
fillAvoidanceTargetObjects(data, debug);

Expand Down Expand Up @@ -1066,18 +1072,35 @@
: 0.0;
const auto offset =
object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal;
const auto to_shift_end = o.longitudinal - offset;

Check warning on line 1075 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#L1075

Added line #L1075 was not covered by tests
const auto path_front_to_ego =
avoid_data_.arclength_from_ego.at(avoid_data_.ego_closest_path_index);

al_avoid.start_longitudinal =
std::max(o.longitudinal - offset - feasible_avoid_distance, 1e-3);
// start point (use previous linear shift length as start shift length.)
al_avoid.start_longitudinal = [&]() {

Check warning on line 1080 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#L1080

Added line #L1080 was not covered by tests
const auto nearest_avoid_distance = std::max(to_shift_end - feasible_avoid_distance, 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);

Check warning on line 1088 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#L1088

Added line #L1088 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);
}();

al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength(
avoid_data_.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego);
al_avoid.start = avoid_data_.reference_path.points.at(al_avoid.start_idx).point.pose;
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_longitudinal = o.longitudinal - offset;
al_avoid.end_longitudinal = to_shift_end;

// misc
al_avoid.id = getOriginalShiftLineUniqueId();
al_avoid.object = o;
al_avoid.object_on_right = utils::avoidance::isOnRight(o);
Expand All @@ -1086,18 +1109,24 @@
AvoidLine al_return;
{
const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length;
// The end_margin also has the purpose of preventing the return path from NOT being
// triggered at the end point.
const auto return_remaining_distance = std::max(
data.arclength_from_ego.back() - o.longitudinal - offset -
parameters_->remain_buffer_distance,
0.0);
const auto to_shift_start = o.longitudinal + offset;

Check warning on line 1112 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#L1112

Added line #L1112 was not covered by tests

// start point
al_return.start_shift_length = feasible_shift_length.get();
al_return.start_longitudinal = to_shift_start;

Check warning on line 1116 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#L1116

Added line #L1116 was not covered by tests

// end point
al_return.end_longitudinal = [&]() {

Check warning on line 1119 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#L1119

Added line #L1119 was not covered by tests
if (data.to_return_point > to_shift_start) {
return std::clamp(
data.to_return_point, to_shift_start, feasible_return_distance + to_shift_start);
}

return to_shift_start + feasible_return_distance;

Check warning on line 1125 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#L1125

Added line #L1125 was not covered by tests
}();
al_return.end_shift_length = 0.0;
al_return.start_longitudinal = o.longitudinal + offset;
al_return.end_longitudinal =
o.longitudinal + offset + std::min(feasible_return_distance, return_remaining_distance);

// misc

Check warning on line 1129 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 41 to 43, 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.
al_return.id = getOriginalShiftLineUniqueId();
al_return.object = o;
al_return.object_on_right = utils::avoidance::isOnRight(o);
Expand Down Expand Up @@ -1795,7 +1824,9 @@
return ret;
}

const auto remaining_distance = arclength_from_ego.back() - parameters_->remain_buffer_distance;
const auto remaining_distance = std::min(
arclength_from_ego.back() - parameters_->dead_line_buffer_for_goal,

Check warning on line 1828 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#L1828

Added line #L1828 was not covered by tests
avoid_data_.to_return_point);

Check warning on line 1829 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::addReturnShiftLine already has high cyclomatic complexity, and now it increases in Lines of Code from 135 to 137. 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.

// If the avoidance point has already been set, the return shift must be set after the point.
const auto last_sl_distance = avoid_data_.arclength_from_ego.at(last_sl.end_idx);
Expand Down Expand Up @@ -2859,8 +2890,8 @@
{
const auto & data = avoid_data_;

if (!planner_data_->route_handler->isInGoalRouteSection(data.current_lanelets.back())) {
RCLCPP_DEBUG(getLogger(), "goal is far enough.");
if (data.to_return_point > planner_data_->parameters.forward_path_length) {
RCLCPP_DEBUG(getLogger(), "return dead line is far enough.");
return;
}

Expand All @@ -2872,10 +2903,7 @@
}

const auto min_return_distance = helper_.getMinAvoidanceDistance(shift_length);

const auto to_goal = calcSignedArcLength(
shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1);
const auto to_stop_line = to_goal - min_return_distance - parameters_->remain_buffer_distance;
const auto to_stop_line = data.to_return_point - min_return_distance;

Check warning on line 2906 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#L2906

Added line #L2906 was not covered by tests

// If we don't need to consider deceleration constraints, insert a deceleration point
// and return immediately
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -218,14 +218,24 @@
{
std::string ns = "avoidance.avoidance.longitudinal.";
p.prepare_time = getOrDeclareParameter<double>(*node, ns + "prepare_time");
p.min_prepare_distance = getOrDeclareParameter<double>(*node, ns + "min_prepare_distance");
p.remain_buffer_distance = getOrDeclareParameter<double>(*node, ns + "remain_buffer_distance");
p.min_slow_down_speed = getOrDeclareParameter<double>(*node, ns + "min_slow_down_speed");
p.buf_slow_down_speed = getOrDeclareParameter<double>(*node, ns + "buf_slow_down_speed");
p.nominal_avoidance_speed =
getOrDeclareParameter<double>(*node, ns + "nominal_avoidance_speed");
}

// avoidance maneuver (return shift dead line)
{
std::string ns = "avoidance.avoidance.return_dead_line.";
p.enable_dead_line_for_goal = getOrDeclareParameter<bool>(*node, ns + "goal.enable");
p.enable_dead_line_for_traffic_light =
getOrDeclareParameter<bool>(*node, ns + "traffic_light.enable");
p.dead_line_buffer_for_goal = getOrDeclareParameter<double>(*node, ns + "goal.buffer");
p.dead_line_buffer_for_traffic_light =
getOrDeclareParameter<double>(*node, ns + "traffic_light.buffer");
}

Check warning on line 238 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 already has high cyclomatic complexity, and now it increases in Lines of Code from 245 to 253. 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.
// yield
{
std::string ns = "avoidance.yield.";
Expand Down
140 changes: 140 additions & 0 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 1380 to 1493, 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 5.43 to 5.39, 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 @@ -48,6 +48,7 @@
namespace behavior_path_planner::utils::avoidance
{

using autoware_perception_msgs::msg::TrafficSignalElement;
using motion_utils::calcLongitudinalOffsetPoint;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestIndex;
Expand Down Expand Up @@ -225,6 +226,86 @@
{
base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end());
}

bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color)
{
const auto it_lamp =
std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) {
return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color;
});

return it_lamp != tl_state.elements.end();
}

bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape)
{
const auto it_lamp = std::find_if(
tl_state.elements.begin(), tl_state.elements.end(),
[&lamp_shape](const auto & x) { return x.shape == lamp_shape; });

return it_lamp != tl_state.elements.end();
}

bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state)

Check warning on line 249 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#L249

Added line #L249 was not covered by tests
{
if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) {
return false;
}

if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN)) {
return false;
}

const std::string turn_direction = lanelet.attributeOr("turn_direction", "else");

if (turn_direction == "else") {
return true;
}
if (
turn_direction == "right" &&
hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) {
return false;
}
if (
turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) {
return false;
}
if (
turn_direction == "straight" &&
hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) {
return false;

Check warning on line 276 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#L276

Added line #L276 was not covered by tests
}

return true;
}

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

isTrafficSignalStop has a cyclomatic complexity of 10, 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.

std::optional<double> calcDistanceToRedTrafficLight(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data)
{
for (const auto & lanelet : lanelets) {
for (const auto & element : lanelet.regulatoryElementsAs<TrafficLight>()) {
const auto traffic_signal_stamped = planner_data->getTrafficSignal(element->id());
if (!traffic_signal_stamped.has_value()) {
continue;

Check warning on line 290 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#L290

Added line #L290 was not covered by tests
}

if (!isTrafficSignalStop(lanelet, traffic_signal_stamped.value().signal)) {
continue;

Check warning on line 294 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#L294

Added line #L294 was not covered by tests
}

const auto & ego_pos = planner_data->self_odometry->pose.pose.position;

Check warning on line 297 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#L297

Added line #L297 was not covered by tests
lanelet::ConstLineString3d stop_line = *(element->stopLine());
const auto x = 0.5 * (stop_line.front().x() + stop_line.back().x());
const auto y = 0.5 * (stop_line.front().y() + stop_line.back().y());
const auto z = 0.5 * (stop_line.front().z() + stop_line.back().z());

return calcSignedArcLength(path.points, ego_pos, tier4_autoware_utils::createPoint(x, y, z));
}
}

return std::nullopt;
}
} // namespace

bool isOnRight(const ObjectData & obj)
Expand Down Expand Up @@ -1840,4 +1921,63 @@

return current_drivable_lanes;
}

double calcDistanceToAvoidStartLine(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (lanelets.empty()) {
return std::numeric_limits<double>::lowest();
}

double distance_to_return_dead_line = std::numeric_limits<double>::lowest();

// dead line stop factor(traffic light)
if (parameters->enable_dead_line_for_traffic_light) {
const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data);
if (to_traffic_light.has_value()) {
distance_to_return_dead_line = std::max(

Check warning on line 1940 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#L1940

Added line #L1940 was not covered by tests
distance_to_return_dead_line,
to_traffic_light.value() + parameters->dead_line_buffer_for_traffic_light);
}
}

return distance_to_return_dead_line;
}

double calcDistanceToReturnDeadLine(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (lanelets.empty()) {
return std::numeric_limits<double>::max();
}

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

// dead line stop factor(traffic light)
if (parameters->enable_dead_line_for_traffic_light) {
const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data);
if (to_traffic_light.has_value()) {
distance_to_return_dead_line = std::min(

Check warning on line 1964 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#L1964

Added line #L1964 was not covered by tests
distance_to_return_dead_line,
to_traffic_light.value() - parameters->dead_line_buffer_for_traffic_light);
}
}

// dead line for goal
if (parameters->enable_dead_line_for_goal) {
if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) {
const auto & ego_pos = planner_data->self_odometry->pose.pose.position;

Check warning on line 1973 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#L1973

Added line #L1973 was not covered by tests
const auto to_goal_distance =
calcSignedArcLength(path.points, ego_pos, path.points.size() - 1);
distance_to_return_dead_line = std::min(

Check warning on line 1976 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#L1975-L1976

Added lines #L1975 - L1976 were not covered by tests
distance_to_return_dead_line, to_goal_distance - parameters->dead_line_buffer_for_goal);
}
}

return distance_to_return_dead_line;
}

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

calcDistanceToReturnDeadLine has 2 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.
} // namespace behavior_path_planner::utils::avoidance
Loading