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(intersection): memorize last observed valid traffic light information #6272

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
43 changes: 41 additions & 2 deletions planning/behavior_velocity_intersection_module/src/debug.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 64.00% to 62.50%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// 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 @@ -111,7 +111,7 @@
return msg;
}

visualization_msgs::msg::MarkerArray createLineMarkerArray(
visualization_msgs::msg::MarkerArray createArrowLineMarkerArray(

Check warning on line 114 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Code Duplication

The module contains 2 functions with similar structure: createArrowLineMarkerArray,createLineMarkerArray. Avoid duplicated, aka copy-pasted, code inside the module. More duplication lowers the code health.

Check notice on line 114 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

createArrowLineMarkerArray has 7 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

Check warning on line 114 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L114

Added line #L114 was not covered by tests
const geometry_msgs::msg::Point & point_start, const geometry_msgs::msg::Point & point_end,
const std::string & ns, const int64_t id, const double r, const double g, const double b)
{
Expand All @@ -137,6 +137,28 @@
return msg;
}

visualization_msgs::msg::MarkerArray createLineMarkerArray(

Check warning on line 140 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L140

Added line #L140 was not covered by tests
const geometry_msgs::msg::Point & point_start, const geometry_msgs::msg::Point & point_end,
const std::string & ns, const int64_t id, const double r, const double g, const double b)
{
visualization_msgs::msg::MarkerArray msg;

visualization_msgs::msg::Marker marker;
marker.header.frame_id = "map";
marker.ns = ns + "_line";
marker.id = id;

Check warning on line 149 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L149

Added line #L149 was not covered by tests
marker.lifetime = rclcpp::Duration::from_seconds(0.3);
marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
marker.action = visualization_msgs::msg::Marker::ADD;
marker.scale.x = 0.1;
marker.color = createMarkerColor(r, g, b, 0.999);

Check warning on line 154 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L151-L154

Added lines #L151 - L154 were not covered by tests
marker.points.push_back(point_start);
marker.points.push_back(point_end);

msg.markers.push_back(marker);
return msg;
}

Check warning on line 160 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L159-L160

Added lines #L159 - L160 were not covered by tests

[[maybe_unused]] visualization_msgs::msg::Marker createPointMarkerArray(
const geometry_msgs::msg::Point & point, const std::string & ns, const int64_t id, const double r,
const double g, const double b)
Expand Down Expand Up @@ -362,10 +384,27 @@
if (debug_data_.nearest_occlusion_projection) {
const auto [point_start, point_end] = debug_data_.nearest_occlusion_projection.value();
appendMarkerArray(
::createLineMarkerArray(
::createArrowLineMarkerArray(
point_start, point_end, "nearest_occlusion_projection", lane_id_, 0.5, 0.5, 0.0),
&debug_marker_array, now);
}

if (debug_data_.traffic_light_observation) {
const auto GREEN = autoware_perception_msgs::msg::TrafficSignalElement::GREEN;
const auto YELLOW = autoware_perception_msgs::msg::TrafficSignalElement::AMBER;

const auto [ego, tl_point, id, color] = debug_data_.traffic_light_observation.value();
geometry_msgs::msg::Point tl_point_point;
tl_point_point.x = tl_point.x();
tl_point_point.y = tl_point.y();
tl_point_point.z = tl_point.z();

Check warning on line 400 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L400

Added line #L400 was not covered by tests
const auto tl_color = (color == GREEN) ? green : (color == YELLOW ? yellow : red);
const auto [r, g, b] = tl_color;
appendMarkerArray(
::createLineMarkerArray(
ego.position, tl_point_point, "intersection_traffic_light", lane_id_, r, g, b),
&debug_marker_array, now);
}

Check warning on line 407 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::createDebugMarkerArray increases in cyclomatic complexity from 18 to 21, 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 debug_marker_array;
}

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

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection.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 1106 to 1134, 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_velocity_intersection_module/src/scene_intersection.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.42 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 All @@ -18,6 +18,7 @@

#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp> // for toGeomPoly
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp> // for toPolygon2d
Expand Down Expand Up @@ -1142,26 +1143,12 @@

bool IntersectionModule::isGreenSolidOn() const
{
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
const auto & lane = lanelet_map_ptr->laneletLayer.get(lane_id_);

std::optional<lanelet::Id> tl_id = std::nullopt;
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
tl_id = tl_reg_elem->id();
break;
}
if (!tl_id) {
// this lane has no traffic light
return false;
}
const auto tl_info_opt = planner_data_->getTrafficSignal(
tl_id.value(), true /* traffic light module keeps last observation*/);
if (!tl_info_opt) {
// the info of this traffic light is not available
if (!last_tl_valid_observation_) {
return false;
}
const auto & tl_info = tl_info_opt.value();
const auto & tl_info = last_tl_valid_observation_.value();

Check notice on line 1151 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

IntersectionModule::isGreenSolidOn is no longer above the threshold for cyclomatic complexity. 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.
for (auto && tl_light : tl_info.signal.elements) {
if (
tl_light.color == TrafficSignalElement::GREEN &&
Expand All @@ -1176,38 +1163,88 @@
{
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;

auto corresponding_arrow = [&](const TrafficSignalElement & element) {

Check warning on line 1166 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1166

Added line #L1166 was not covered by tests
if (turn_direction_ == "straight" && element.shape == TrafficSignalElement::UP_ARROW) {
return true;
}
if (turn_direction_ == "left" && element.shape == TrafficSignalElement::LEFT_ARROW) {
return true;
}
if (turn_direction_ == "right" && element.shape == TrafficSignalElement::RIGHT_ARROW) {
return true;

Check warning on line 1174 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1174

Added line #L1174 was not covered by tests
}
return false;
};

// ==========================================================================================
// if no traffic light information has been available, it is UNKNOWN state which is treated as
// NOT_PRIORITIZED
//
// if there has been any information available in the past more than once, the last valid
// information is kept and used for planning
// ==========================================================================================
auto level = TrafficPrioritizedLevel::NOT_PRIORITIZED;
if (last_tl_valid_observation_) {
auto color = TrafficSignalElement::GREEN;
const auto & tl_info = last_tl_valid_observation_.value();
bool has_amber_signal{false};
for (auto && tl_light : tl_info.signal.elements) {
if (

Check warning on line 1192 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1192

Added line #L1192 was not covered by tests
tl_light.color == TrafficSignalElement::AMBER &&
tl_light.shape == TrafficSignalElement::CIRCLE) {
has_amber_signal = true;
}
if (
(tl_light.color == TrafficSignalElement::RED &&
tl_light.shape == TrafficSignalElement::CIRCLE) ||
(tl_light.color == TrafficSignalElement::GREEN && corresponding_arrow(tl_light))) {

Check warning on line 1200 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

IntersectionModule::getTrafficPrioritizedLevel has 1 complex conditionals with 3 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
// NOTE: Return here since the red signal has the highest priority.
level = TrafficPrioritizedLevel::FULLY_PRIORITIZED;
color = TrafficSignalElement::RED;
break;
}
}
if (has_amber_signal) {
level = TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED;
color = TrafficSignalElement::AMBER;
}
if (tl_id_and_point_) {
const auto [tl_id, point] = tl_id_and_point_.value();
debug_data_.traffic_light_observation =
std::make_tuple(planner_data_->current_odometry->pose, point, tl_id, color);
}
}
return level;

Check warning on line 1217 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1217

Added line #L1217 was not covered by tests
}

void IntersectionModule::updateTrafficSignalObservation()

Check warning on line 1220 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1220

Added line #L1220 was not covered by tests
{
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
const auto & lane = lanelet_map_ptr->laneletLayer.get(lane_id_);

std::optional<lanelet::Id> tl_id = std::nullopt;
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
tl_id = tl_reg_elem->id();
break;
if (!tl_id_and_point_) {
for (auto && tl_reg_elem :

Check warning on line 1226 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1226

Added line #L1226 was not covered by tests
lane.regulatoryElementsAs<lanelet::autoware::AutowareTrafficLight>()) {
for (const auto & ls : tl_reg_elem->lightBulbs()) {
if (ls.hasAttribute("traffic_light_id")) {
tl_id_and_point_ = std::make_pair(tl_reg_elem->id(), ls.front());
break;

Check warning on line 1231 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1230-L1231

Added lines #L1230 - L1231 were not covered by tests
}
}
}

Check warning on line 1234 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1233-L1234

Added lines #L1233 - L1234 were not covered by tests
}
if (!tl_id) {
if (!tl_id_and_point_) {
// this lane has no traffic light
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
return;
}
const auto tl_info_opt = planner_data_->getTrafficSignal(
tl_id.value(), true /* traffic light module keeps last observation*/);
const auto [tl_id, point] = tl_id_and_point_.value();
const auto tl_info_opt =
planner_data_->getTrafficSignal(tl_id, true /* traffic light module keeps last observation*/);
if (!tl_info_opt) {
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
}
const auto & tl_info = tl_info_opt.value();
bool has_amber_signal{false};
for (auto && tl_light : tl_info.signal.elements) {
if (tl_light.color == TrafficSignalElement::AMBER) {
has_amber_signal = true;
}
if (tl_light.color == TrafficSignalElement::RED) {
// NOTE: Return here since the red signal has the highest priority.
return TrafficPrioritizedLevel::FULLY_PRIORITIZED;
}
}
if (has_amber_signal) {
return TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED;
// the info of this traffic light is not available
return;
}
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
last_tl_valid_observation_ = tl_info_opt.value();

Check notice on line 1247 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

IntersectionModule::getTrafficPrioritizedLevel increases in cyclomatic complexity from 10 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.

Check notice on line 1247 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Deep, Nested Complexity

IntersectionModule::updateTrafficSignalObservation has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
}

IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStatus(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,9 @@ class IntersectionModule : public SceneModuleInterface
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
nearest_occlusion_projection{std::nullopt};
std::optional<double> static_occlusion_with_traffic_light_timeout{std::nullopt};

std::optional<std::tuple<geometry_msgs::msg::Pose, lanelet::ConstPoint3d, lanelet::Id, uint8_t>>
traffic_light_observation{std::nullopt};
};

using TimeDistanceArray = std::vector<std::pair<double /* time*/, double /* distance*/>>;
Expand Down Expand Up @@ -388,6 +391,20 @@ class IntersectionModule : public SceneModuleInterface
intersection::ObjectInfoManager object_info_manager_;
/** @} */

private:
/**
***********************************************************
***********************************************************
***********************************************************
* @defgroup collision-variables [var] collision detection
* @{
*/
//! save the last UNKNOWN traffic light information of this intersection(keep even if the info got
//! unavailable)
std::optional<std::pair<lanelet::Id, lanelet::ConstPoint3d>> tl_id_and_point_;
std::optional<TrafficSignalStamped> last_tl_valid_observation_{std::nullopt};
/** @} */

private:
/**
***********************************************************
Expand Down Expand Up @@ -556,6 +573,13 @@ class IntersectionModule : public SceneModuleInterface
* @brief find TrafficPrioritizedLevel
*/
TrafficPrioritizedLevel getTrafficPrioritizedLevel() const;

/**
* @brief update the valid traffic signal information if still available, otherwise keep last
* observation
*/
void updateTrafficSignalObservation();

/** @} */

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

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.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 12.82 to 12.91, 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 @@ -258,19 +258,27 @@
planner_data_->occupancy_grid->info.resolution);
}

const bool is_green_solid_on = isGreenSolidOn();
if (is_green_solid_on && !initial_green_light_observed_time_) {
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
const bool approached_assigned_lane =
motion_utils::calcSignedArcLength(
path->points, closest_idx,
tier4_autoware_utils::createPoint(
assigned_lane_begin_point.x(), assigned_lane_begin_point.y(),
assigned_lane_begin_point.z())) <
planner_param_.collision_detection.yield_on_green_traffic_light
.distance_to_assigned_lanelet_start;
if (approached_assigned_lane) {
initial_green_light_observed_time_ = clock_->now();
// ==========================================================================================
// update traffic light information
// updateTrafficSignalObservation() must be called at first to because other traffic signal
// fuctions use last_valid_observation_
// ==========================================================================================
if (has_traffic_light_) {
updateTrafficSignalObservation();
const bool is_green_solid_on = isGreenSolidOn();
if (is_green_solid_on && !initial_green_light_observed_time_) {
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
const bool approached_assigned_lane =
motion_utils::calcSignedArcLength(

Check warning on line 272 in planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp#L272

Added line #L272 was not covered by tests
path->points, closest_idx,
tier4_autoware_utils::createPoint(

Check warning on line 274 in planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp#L274

Added line #L274 was not covered by tests
assigned_lane_begin_point.x(), assigned_lane_begin_point.y(),
assigned_lane_begin_point.z())) <
planner_param_.collision_detection.yield_on_green_traffic_light
.distance_to_assigned_lanelet_start;

Check warning on line 278 in planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp#L278

Added line #L278 was not covered by tests
if (approached_assigned_lane) {
initial_green_light_observed_time_ = clock_->now();
}

Check warning on line 281 in planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::prepareIntersectionData increases in cyclomatic complexity from 14 to 15, 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.
}
}

Expand Down
Loading