MavlinkStream: Ensure that not multiple messages are sent after some time sending nothing

This commit is contained in:
acfloria 2018-03-13 17:40:33 +01:00 committed by Beat Küng
parent 0e89a6b8bd
commit 63cb895a1d

View File

@ -118,11 +118,12 @@ MavlinkStream::update(const hrt_abstime t)
sent = send(t);
#endif
// If the interval is non-zero do not use the actual time but
// increment at a fixed rate, so that processing delays do not
// distort the average rate
// If the interval is non-zero and dt is smaller than 1.5 times the interval
// do not use the actual time but increment at a fixed rate, so that processing delays do not
// distort the average rate. The check of the maximum interval is done to ensure that after a long time
// not sending anything multiple messages in a short time are sent.
if (sent) {
_last_sent = (interval > 0) ? _last_sent + interval : t;
_last_sent = ((interval > 0) && ((int64_t)(1.5 * interval) > dt)) ? _last_sent + interval : t;
return 0;
} else {