diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 28eb2945f9..582cffb2dd 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1249,7 +1249,6 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ deferred_message_bucket[empty_bucket_id].interval_ms = interval_ms; deferred_message_bucket[empty_bucket_id].last_sent_ms = AP_HAL::millis16(); closest_bucket = empty_bucket_id; - closest_bucket_interval_delta = 0; } deferred_message_bucket[closest_bucket].ap_message_ids.set(id);