mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Tools: autotest: give message rate in drain
This commit is contained in:
parent
622549456c
commit
22cc55a500
@ -352,9 +352,12 @@ class AutoTest(ABC):
|
|||||||
|
|
||||||
def drain_mav(self):
|
def drain_mav(self):
|
||||||
count = 0
|
count = 0
|
||||||
|
tstart = time.time()
|
||||||
while self.mav.recv_match(type='SYSTEM_TIME', blocking=False) is not None:
|
while self.mav.recv_match(type='SYSTEM_TIME', blocking=False) is not None:
|
||||||
count += 1
|
count += 1
|
||||||
self.progress("Drained %u messages from mav" % count)
|
tdelta = time.time() - tstart
|
||||||
|
self.progress("Drained %u messages from mav (%f/s)" % (
|
||||||
|
count, count/float(tdelta)))
|
||||||
|
|
||||||
#################################################
|
#################################################
|
||||||
# SIM UTILITIES
|
# SIM UTILITIES
|
||||||
|
Loading…
Reference in New Issue
Block a user