From e08a8d03d2b2bd1301517d2749ad49be610bebdb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Dec 2018 17:19:42 +1100 Subject: [PATCH] GCS_MAVLink: initialise last_sent_ms when reusing bucket --- libraries/GCS_MAVLink/GCS_Common.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9942fae2d7..4f97f7662c 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1341,6 +1341,7 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ closest_bucket_interval_delta = 0; } else if (deferred_message_bucket[closest_bucket].ap_message_ids.count() == 0) { deferred_message_bucket[closest_bucket].interval_ms = interval_ms; + deferred_message_bucket[closest_bucket].last_sent_ms = AP_HAL::millis16(); } deferred_message_bucket[closest_bucket].ap_message_ids.set(id);