From b3837ee911d0fbdb105f36a4e1ec08fb3d24ab1d Mon Sep 17 00:00:00 2001
From: Michael du Breuil <wicked.shell.scripts@gmail.com>
Date: Tue, 27 Jun 2023 11:38:15 -0700
Subject: [PATCH] AP_ADSB: Fix spam of lost transciever message at update()
 rate

---
 libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
index 14a3b04808..eeeec516bc 100644
--- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
+++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
@@ -43,8 +43,8 @@ void AP_ADSB_uAvionix_MAVLink::update()
     // send static configuration data to transceiver, every 5s
     if (_frontend.out_state.chan_last_ms > 0 && now - _frontend.out_state.chan_last_ms > ADSB_CHAN_TIMEOUT_MS) {
         // haven't gotten a heartbeat health status packet in a while, assume hardware failure
-        // TODO: reset out_state.chan
         _frontend.out_state.chan = -1;
+        _frontend.out_state.chan_last_ms = 0; // if the time isn't reset we spam the message
         gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out");
     } else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) {
         const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan);