Skip to content

Commit 3dc9605

Browse files
feat(autoware_traffic_light_arbiter): add current time validation (#9747)
* add current time validation Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> * style(pre-commit): autofix * change ros parameter name Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> * style(pre-commit): autofix * add validation with absolute function Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> * add timestamp of topic in test Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> * fix ci error Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> --------- Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent a5aeb82 commit 3dc9605

File tree

5 files changed

+32
-4
lines changed

5 files changed

+32
-4
lines changed

perception/autoware_traffic_light_arbiter/README.md

+3-2
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,8 @@ The table below outlines how the matching process determines the output based on
4343

4444
| Name | Type | Default Value | Description |
4545
| --------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
46-
| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging |
47-
| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging |
46+
| `external_delay_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with current time |
47+
| `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 |
48+
| `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 |
4849
| `external_priority` | bool | false | Whether or not externals signals take precedence over perception-based ones. If false, the merging uses confidence as a criteria |
4950
| `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 |

perception/autoware_traffic_light_arbiter/config/traffic_light_arbiter.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
/**:
22
ros__parameters:
3+
external_delay_tolerance: 5.0
34
external_time_tolerance: 5.0
45
perception_time_tolerance: 1.0
56
external_priority: false

perception/autoware_traffic_light_arbiter/include/autoware/traffic_light_arbiter/traffic_light_arbiter.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ class TrafficLightArbiter : public rclcpp::Node
5151

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

54+
double external_delay_tolerance_;
5455
double external_time_tolerance_;
5556
double perception_time_tolerance_;
5657
bool external_priority_;

perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp

+17-2
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <lanelet2_core/LaneletMap.h>
2121
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
2222

23+
#include <algorithm>
2324
#include <map>
2425
#include <memory>
2526
#include <tuple>
@@ -70,6 +71,7 @@ namespace autoware
7071
TrafficLightArbiter::TrafficLightArbiter(const rclcpp::NodeOptions & options)
7172
: Node("traffic_light_arbiter", options)
7273
{
74+
external_delay_tolerance_ = this->declare_parameter<double>("external_delay_tolerance", 5.0);
7375
external_time_tolerance_ = this->declare_parameter<double>("external_time_tolerance", 5.0);
7476
perception_time_tolerance_ = this->declare_parameter<double>("perception_time_tolerance", 1.0);
7577
external_priority_ = this->declare_parameter<bool>("external_priority", false);
@@ -119,7 +121,7 @@ void TrafficLightArbiter::onPerceptionMsg(const TrafficSignalArray::ConstSharedP
119121
latest_perception_msg_ = *msg;
120122

121123
if (
122-
(rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds() >
124+
std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds()) >
123125
external_time_tolerance_) {
124126
latest_external_msg_.traffic_light_groups.clear();
125127
}
@@ -129,10 +131,16 @@ void TrafficLightArbiter::onPerceptionMsg(const TrafficSignalArray::ConstSharedP
129131

130132
void TrafficLightArbiter::onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg)
131133
{
134+
if (std::abs((this->now() - rclcpp::Time(msg->stamp)).seconds()) > external_delay_tolerance_) {
135+
RCLCPP_WARN_THROTTLE(
136+
get_logger(), *get_clock(), 5000, "Received outdated V2X traffic signal messages");
137+
return;
138+
}
139+
132140
latest_external_msg_ = *msg;
133141

134142
if (
135-
(rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds() >
143+
std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds()) >
136144
perception_time_tolerance_) {
137145
latest_perception_msg_.traffic_light_groups.clear();
138146
}
@@ -229,6 +237,13 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim
229237
}
230238

231239
pub_->publish(output_signals_msg);
240+
241+
const auto latest_time =
242+
std::max(rclcpp::Time(latest_perception_msg_.stamp), rclcpp::Time(latest_external_msg_.stamp));
243+
if (rclcpp::Time(output_signals_msg.stamp) < latest_time) {
244+
RCLCPP_WARN_THROTTLE(
245+
get_logger(), *get_clock(), 5000, "Published traffic signal messages are not latest");
246+
}
232247
}
233248
} // namespace autoware
234249

perception/autoware_traffic_light_arbiter/test/test_node.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyPerceptionMsg)
196196
};
197197
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);
198198

199+
// stamp preparation
200+
perception_msg.stamp = test_target_node->now();
201+
199202
test_manager->test_pub_msg<LaneletMapBin>(
200203
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
201204
test_manager->test_pub_msg<TrafficSignalArray>(
@@ -229,6 +232,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyExternalMsg)
229232
};
230233
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);
231234

235+
// stamp preparation
236+
external_msg.stamp = test_target_node->now();
237+
232238
test_manager->test_pub_msg<LaneletMapBin>(
233239
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
234240
test_manager->test_pub_msg<TrafficSignalArray>(
@@ -268,6 +274,10 @@ TEST(TrafficLightArbiterTest, testTrafficSignalBothMsg)
268274
};
269275
test_manager->set_subscriber<TrafficSignalArray>(output_topic, callback);
270276

277+
// stamp preparation
278+
external_msg.stamp = test_target_node->now();
279+
perception_msg.stamp = test_target_node->now();
280+
271281
test_manager->test_pub_msg<LaneletMapBin>(
272282
test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local());
273283
test_manager->test_pub_msg<TrafficSignalArray>(

0 commit comments

Comments
 (0)