mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: change order in removing message from bucket
A call to find_next_bucket_to_send would change sending_bucket_id so the if would have a wrong meaning The call also changes the bucket_message_ids_to_send so currently there is no bug, but it can change
This commit is contained in:
parent
6f01073786
commit
a50a9c65ad
@ -1236,6 +1236,11 @@ void GCS_MAVLINK::update_send()
|
||||
void GCS_MAVLINK::remove_message_from_bucket(int8_t bucket, ap_message id)
|
||||
{
|
||||
deferred_message_bucket[bucket].ap_message_ids.clear(id);
|
||||
|
||||
if (bucket == sending_bucket_id) {
|
||||
bucket_message_ids_to_send.clear(id);
|
||||
}
|
||||
|
||||
if (deferred_message_bucket[bucket].ap_message_ids.count() == 0) {
|
||||
// bucket empty. Free it:
|
||||
deferred_message_bucket[bucket].interval_ms = 0;
|
||||
@ -1244,10 +1249,6 @@ void GCS_MAVLINK::remove_message_from_bucket(int8_t bucket, ap_message id)
|
||||
find_next_bucket_to_send();
|
||||
}
|
||||
}
|
||||
|
||||
if (bucket == sending_bucket_id) {
|
||||
bucket_message_ids_to_send.clear(id);
|
||||
}
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ms)
|
||||
|
Loading…
Reference in New Issue
Block a user