mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Tools: autotest: make drain_mav truly drain the mavlink connection
This commit is contained in:
parent
281dbfcef8
commit
f71f100d6a
@ -282,8 +282,7 @@ class AutoTest(ABC):
|
|||||||
pass
|
pass
|
||||||
|
|
||||||
# empty mav to avoid getting old timestamps:
|
# empty mav to avoid getting old timestamps:
|
||||||
while self.mav.recv_match(blocking=False):
|
self.drain_mav()
|
||||||
pass
|
|
||||||
|
|
||||||
self.initialise_after_reboot_sitl()
|
self.initialise_after_reboot_sitl()
|
||||||
|
|
||||||
@ -395,7 +394,7 @@ class AutoTest(ABC):
|
|||||||
def drain_mav(self):
|
def drain_mav(self):
|
||||||
count = 0
|
count = 0
|
||||||
tstart = time.time()
|
tstart = time.time()
|
||||||
while self.mav.recv_match(type='SYSTEM_TIME', blocking=False) is not None:
|
while self.mav.recv_match(blocking=False) is not None:
|
||||||
count += 1
|
count += 1
|
||||||
tdelta = time.time() - tstart
|
tdelta = time.time() - tstart
|
||||||
if tdelta == 0:
|
if tdelta == 0:
|
||||||
|
Loading…
Reference in New Issue
Block a user