From dec615bfb5e567d227201c87b49c6b0fe55565ab Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 May 2020 11:39:10 +1000 Subject: [PATCH] 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. --- Tools/autotest/common.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 0182507f9e..350358c7ae 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -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)