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(autoware_traffic_light_arbiter): add current time validation #9747

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
5 changes: 3 additions & 2 deletions perception/autoware_traffic_light_arbiter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,8 @@ The table below outlines how the matching process determines the output based on

| Name | Type | Default Value | Description |
| --------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging |
| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging |
| `external_delay_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with current time |
| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with a timestamp of perception message |
| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging in comparison with a timestamp of external message |
| `external_priority` | bool | false | Whether or not externals signals take precedence over perception-based ones. If false, the merging uses confidence as a criteria |
| `enable_signal_matching` | bool | false | Decide whether to validate the match between perception signals and external signals. If set to true, verify that the colors match and only publish them if they are identical |
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
/**:
ros__parameters:
external_delay_tolerance: 5.0
external_time_tolerance: 5.0
perception_time_tolerance: 1.0
external_priority: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ class TrafficLightArbiter : public rclcpp::Node

std::unique_ptr<std::unordered_set<lanelet::Id>> map_regulatory_elements_set_;

double external_delay_tolerance_;
double external_time_tolerance_;
double perception_time_tolerance_;
bool external_priority_;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 The Autoware Contributors

Check notice on line 1 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Code Duplication

The module no longer contains too many functions with similar structure

Check notice on line 1 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.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.14 to 4.43, 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 @@ -20,6 +20,7 @@
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>

#include <algorithm>
#include <map>
#include <memory>
#include <tuple>
Expand Down Expand Up @@ -70,6 +71,7 @@
TrafficLightArbiter::TrafficLightArbiter(const rclcpp::NodeOptions & options)
: Node("traffic_light_arbiter", options)
{
external_delay_tolerance_ = this->declare_parameter<double>("external_delay_tolerance", 5.0);
external_time_tolerance_ = this->declare_parameter<double>("external_time_tolerance", 5.0);
perception_time_tolerance_ = this->declare_parameter<double>("perception_time_tolerance", 1.0);
external_priority_ = this->declare_parameter<bool>("external_priority", false);
Expand Down Expand Up @@ -119,7 +121,7 @@
latest_perception_msg_ = *msg;

if (
(rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds() >
std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds()) >
external_time_tolerance_) {
latest_external_msg_.traffic_light_groups.clear();
}
Expand All @@ -129,10 +131,16 @@

void TrafficLightArbiter::onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg)
{
if (std::abs((this->now() - rclcpp::Time(msg->stamp)).seconds()) > external_delay_tolerance_) {
RCLCPP_WARN_THROTTLE(

Check warning on line 135 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp#L135

Added line #L135 was not covered by tests
get_logger(), *get_clock(), 5000, "Received outdated V2X traffic signal messages");
return;

Check warning on line 137 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp#L137

Added line #L137 was not covered by tests
}

latest_external_msg_ = *msg;

if (
(rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds() >
std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds()) >
perception_time_tolerance_) {
latest_perception_msg_.traffic_light_groups.clear();
}
Expand Down Expand Up @@ -229,6 +237,13 @@
}

pub_->publish(output_signals_msg);

const auto latest_time =
std::max(rclcpp::Time(latest_perception_msg_.stamp), rclcpp::Time(latest_external_msg_.stamp));
if (rclcpp::Time(output_signals_msg.stamp) < latest_time) {
RCLCPP_WARN_THROTTLE(

Check warning on line 244 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp#L244

Added line #L244 was not covered by tests
get_logger(), *get_clock(), 5000, "Published traffic signal messages are not latest");
}

Check warning on line 246 in perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrafficLightArbiter::arbitrateAndPublish increases in cyclomatic complexity from 15 to 16, 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.
}
} // namespace autoware

Expand Down
10 changes: 10 additions & 0 deletions perception/autoware_traffic_light_arbiter/test/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyPerceptionMsg)
};
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);

// stamp preparation
perception_msg.stamp = test_target_node->now();

test_manager->test_pub_msg<LaneletMapBin>(
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
test_manager->test_pub_msg<TrafficSignalArray>(
Expand Down Expand Up @@ -229,6 +232,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyExternalMsg)
};
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);

// stamp preparation
external_msg.stamp = test_target_node->now();

test_manager->test_pub_msg<LaneletMapBin>(
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
test_manager->test_pub_msg<TrafficSignalArray>(
Expand Down Expand Up @@ -268,6 +274,10 @@ TEST(TrafficLightArbiterTest, testTrafficSignalBothMsg)
};
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);

// stamp preparation
external_msg.stamp = test_target_node->now();
perception_msg.stamp = test_target_node->now();

test_manager->test_pub_msg<LaneletMapBin>(
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
test_manager->test_pub_msg<TrafficSignalArray>(
Expand Down
Loading