Browse Source

GCS_MAVLink: divide time allowed to send messages fairly

copter407
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
96c97589ae
  1. 6
      libraries/GCS_MAVLink/GCS.h
  2. 12
      libraries/GCS_MAVLink/GCS_Common.cpp

6
libraries/GCS_MAVLink/GCS.h

@ -932,6 +932,12 @@ private: @@ -932,6 +932,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();

12
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1882,9 +1882,19 @@ void GCS::update_send() @@ -1882,9 +1882,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();
}

Loading…
Cancel
Save