GCS_MAVLink: divide time allowed to send messages fairly

This commit is contained in:
Peter Barker 2020-02-25 15:23:52 +11:00 committed by Andrew Tridgell
parent c6f12e519b
commit fbe2e75b9f
2 changed files with 17 additions and 1 deletions

View File

@ -978,6 +978,12 @@ private:
// timer called to implement pass-thru
void passthru_timer();
// this contains the index of the GCS_MAVLINK backend we will
// first call update_send on. It is incremented each time
// GCS::update_send is called so we don't starve later links of
// time in which they are permitted to send messages.
uint8_t first_backend_to_send;
};
GCS &gcs();

View File

@ -1961,9 +1961,19 @@ void GCS::update_send()
if (_missionitemprotocol_fence != nullptr) {
_missionitemprotocol_fence->update();
}
for (uint8_t i=0; i<num_gcs(); i++) {
// round-robin the GCS_MAVLINK backend that gets to go first so
// one backend doesn't monopolise all of the time allowed for sending
// messages
for (uint8_t i=first_backend_to_send; i<num_gcs(); i++) {
chan(i)->update_send();
}
for (uint8_t i=0; i<first_backend_to_send; i++) {
chan(i)->update_send();
}
first_backend_to_send++;
if (first_backend_to_send >= num_gcs()) {
first_backend_to_send = 0;
}
WITH_SEMAPHORE(_statustext_sem);
service_statustext();
}