diff --git a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp index 3baefaa43163a..f76501cbfe85a 100644 --- a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -111,7 +111,8 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim std::unordered_map> regulatory_element_signals_map; if (map_regulatory_elements_set_ == nullptr) { - RCLCPP_WARN(get_logger(), "Received traffic signal messages before a map"); + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, "Received traffic signal messages before a map"); return; } @@ -126,8 +127,9 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim auto add_signal_function = [&](const auto & signal, bool priority) { const auto id = signal.traffic_signal_id; if (!map_regulatory_elements_set_->count(id)) { - RCLCPP_WARN( - get_logger(), "Received a traffic signal not present in the current map (%lu)", id); + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, + "Received a traffic signal not present in the current map (%lu)", id); return; }