AP_ADSB: Fix spam of lost transciever message at update() rate

This commit is contained in:
Michael du Breuil 2023-06-27 11:38:15 -07:00 committed by Randy Mackay
parent 42e18db221
commit 4cf19a74b4
1 changed files with 1 additions and 1 deletions

View File

@ -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);