Browse Source

GCS_MAVLink: avoid squashing close-together intervals into same bucket

mission-4.1.18
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
c70fec305c
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1332,7 +1332,7 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ @@ -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;

Loading…
Cancel
Save