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): check traffic light info in order to limit drivable area #6016

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 @@ -166,7 +166,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
std::for_each(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
data.drivable_lanes.push_back(utils::avoidance::generateExpandDrivableLanes(
lanelet, planner_data_, avoidance_parameters_));
lanelet, planner_data_, avoidance_parameters_, false));
});

// calc drivable bound
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ 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);
const std::shared_ptr<AvoidanceParameters> & parameters, const bool in_avoidance_maneuver);

double calcDistanceToReturnDeadLine(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
Expand Down
6 changes: 4 additions & 2 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 1114 to 1116, 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.67 to 4.69, 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 @@ -223,10 +223,12 @@
utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_);

// expand drivable lanes
const auto has_shift_point = !path_shifter_.getShiftLines().empty();
const auto in_avoidance_maneuver = has_shift_point || helper_->isShifted();
std::for_each(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
data.drivable_lanes.push_back(
utils::avoidance::generateExpandDrivableLanes(lanelet, planner_data_, parameters_));
data.drivable_lanes.push_back(utils::avoidance::generateExpandDrivableLanes(
lanelet, planner_data_, parameters_, in_avoidance_maneuver));
});

// calc drivable bound
Expand Down
12 changes: 11 additions & 1 deletion planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1699 to 1709, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.09 to 5.14, 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 @@ -1953,30 +1953,40 @@

DrivableLanes generateExpandDrivableLanes(
const lanelet::ConstLanelet & lanelet, const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
const std::shared_ptr<AvoidanceParameters> & parameters, const bool in_avoidance_maneuver)
{
const auto & route_handler = planner_data->route_handler;

DrivableLanes current_drivable_lanes;
current_drivable_lanes.left_lane = lanelet;
current_drivable_lanes.right_lane = lanelet;

if (!parameters->use_adjacent_lane) {
return current_drivable_lanes;
}

// 1. get left/right side lanes
const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
const auto next_lanes = route_handler->getNextLanelets(target_lane);
const auto is_stop_signal = utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data);
if (is_stop_signal && !in_avoidance_maneuver) {
return;
}
const auto all_left_lanelets = route_handler->getAllLeftSharedLinestringLanelets(
target_lane, parameters->use_opposite_lane, true);
if (!all_left_lanelets.empty()) {
current_drivable_lanes.left_lane = all_left_lanelets.back(); // leftmost lanelet
pushUniqueVector(
current_drivable_lanes.middle_lanes,
lanelet::ConstLanelets(all_left_lanelets.begin(), all_left_lanelets.end() - 1));
}
};
const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
const auto next_lanes = route_handler->getNextLanelets(target_lane);
const auto is_stop_signal = utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data);
if (is_stop_signal && !in_avoidance_maneuver) {
return;
}

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

generateExpandDrivableLanes increases in cyclomatic complexity from 24 to 28, 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.
const auto all_right_lanelets = route_handler->getAllRightSharedLinestringLanelets(
target_lane, parameters->use_opposite_lane, true);
if (!all_right_lanelets.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,21 @@ bool isStoppedAtRedTrafficLightWithinDistance(
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data,
const double distance_threshold = std::numeric_limits<double>::infinity());

/**
* @brief Determines if a traffic signal indicates a stop for the given lanelet.
*
* Evaluates the current state of the traffic light, considering if it's green or unknown,
* which would not necessitate a stop. Then, it checks the turn direction attribute of the lanelet
* against the traffic light's arrow shapes to determine whether a vehicle must stop or if it can
* proceed based on allowed turn directions.
*
* @param lanelet The lanelet to check for a stop signal at its traffic light.
* @param planner_data Shared pointer to the planner data containing vehicle state information.
* @return True if the traffic signal indicates a stop is required, false otherwise.
*/
bool isTrafficSignalStop(
const lanelet::ConstLanelets & lanelets, const std::shared_ptr<const PlannerData> & planner_data);
} // namespace behavior_path_planner::utils::traffic_light

#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__TRAFFIC_LIGHT_UTILS_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check warning on line 1 in planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Overall Code Complexity

This module has a mean cyclomatic complexity of 5.57 across 7 functions. The mean complexity threshold is 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 @@ -177,4 +177,24 @@
return (distance_to_red_traffic_light < distance_threshold);
}

bool isTrafficSignalStop(
const lanelet::ConstLanelets & lanelets, 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;
}

if (traffic_light_utils::isTrafficSignalStop(
lanelet, traffic_signal_stamped.value().signal)) {
return true;
}
}
}

return false;
}

} // namespace behavior_path_planner::utils::traffic_light
Loading