mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Tools: autotest: correct division-by-zero error
This commit is contained in:
parent
d71244dd23
commit
429217f392
@ -359,8 +359,12 @@ class AutoTest(ABC):
|
||||
while self.mav.recv_match(type='SYSTEM_TIME', blocking=False) is not None:
|
||||
count += 1
|
||||
tdelta = time.time() - tstart
|
||||
self.progress("Drained %u messages from mav (%f/s)" % (
|
||||
count, count/float(tdelta)))
|
||||
if tdelta == 0:
|
||||
rate = "instantly"
|
||||
else:
|
||||
rate = "%f/s" % (count/float(tdelta),)
|
||||
|
||||
self.progress("Drained %u messages from mav (%s)" % (count, rate))
|
||||
|
||||
#################################################
|
||||
# SIM UTILITIES
|
||||
|
Loading…
Reference in New Issue
Block a user