autotest: drain SITL pexpect when waiting for parameter

This is important when rebooting as the ArduPilot process can block on
sending to stdout, which pexpect is reading from.  While rebooting we're
waiting for a parameter to be reset to a different value in this loop,
which could take quite some time.
This commit is contained in:
Peter Barker 2020-05-14 11:39:10 +10:00 committed by Peter Barker
parent 115751833b
commit dec615bfb5
1 changed files with 5 additions and 0 deletions

View File

@ -2516,6 +2516,11 @@ class AutoTest(ABC):
def get_parameter(self, name, retry=1, timeout=60):
"""Get parameters from vehicle."""
for i in range(0, retry):
# we call get_parameter while the vehicle is rebooting.
# We need to read out the SITL binary's STDOUT or the
# process blocks writing to it.
if self.sitl is not None:
util.pexpect_drain(self.sitl)
self.mavproxy.send("param fetch %s\n" % name)
try:
self.mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/retry)