From c70fec305cd3ba3af7dddeeda09a9577d57d1c4a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Dec 2018 09:52:40 +1100 Subject: [PATCH] GCS_MAVLink: avoid squashing close-together intervals into same bucket --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 41fb1a6952..ba5f0c1258 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1332,7 +1332,7 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ return false; } - if (closest_bucket_interval_delta > 5 && + if (closest_bucket_interval_delta != 0 && empty_bucket_id != -1) { // allocate a bucket for this interval deferred_message_bucket[empty_bucket_id].interval_ms = interval_ms;