mirror of https://github.com/ArduPilot/ardupilot
autotest: drain_mav_unparsed gets a quiet option
This commit is contained in:
parent
b75dd36f71
commit
62f289b8e6
|
@ -910,7 +910,7 @@ class AutoTest(ABC):
|
||||||
continue
|
continue
|
||||||
util.pexpect_drain(p)
|
util.pexpect_drain(p)
|
||||||
|
|
||||||
def drain_mav_unparsed(self):
|
def drain_mav_unparsed(self, quiet=False):
|
||||||
count = 0
|
count = 0
|
||||||
tstart = time.time()
|
tstart = time.time()
|
||||||
while True:
|
while True:
|
||||||
|
@ -918,6 +918,8 @@ class AutoTest(ABC):
|
||||||
if len(this) == 0:
|
if len(this) == 0:
|
||||||
break
|
break
|
||||||
count += len(this)
|
count += len(this)
|
||||||
|
if quiet:
|
||||||
|
return
|
||||||
tdelta = time.time() - tstart
|
tdelta = time.time() - tstart
|
||||||
if tdelta == 0:
|
if tdelta == 0:
|
||||||
rate = "instantly"
|
rate = "instantly"
|
||||||
|
|
Loading…
Reference in New Issue