mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
GCS_MAVLink: avoid squashing close-together intervals into same bucket
This commit is contained in:
parent
e198b0c7e6
commit
c70fec305c
@ -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…
Reference in New Issue
Block a user