Skip to content

Commit

Permalink
AP_ADSB: Fix spam of lost transciever message at update() rate
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell authored and magicrub committed Jun 28, 2023
1 parent 6fafb26 commit 25a118c
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 25a118c

Please sign in to comment.