GCS_MAVLink: initialise last_sent_ms when reusing bucket

This commit is contained in:
Peter Barker 2018-12-05 17:19:42 +11:00 committed by Randy Mackay
parent 09905bb2f2
commit e08a8d03d2
1 changed files with 1 additions and 0 deletions

View File

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