From 96b9c8f59ac5c0084e42052e4485d4faf57c767e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 5 Dec 2019 14:57:26 +1100 Subject: [PATCH] autotest: wait a long time for RC to restart after restarting SITL binary May help fix the "no RC" failures we're seeing in CI --- Tools/autotest/common.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index b542692466..1981ecdefd 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -453,10 +453,17 @@ class AutoTest(ABC): self.stop_SITL() self.start_SITL(customisations=customisations, wipe=False) self.wait_heartbeat() + # we also need to wait for MAVProxy to requests streams again + # - in particular, RC_CHANNELS. + m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=15) + if m is None: + raise NotAchievedException("No RC_CHANNELS message after restarting SITL") def reset_SITL_commandline(self): + self.progress("Resetting SITL commandline to default") self.stop_SITL() self.start_SITL(wipe=False) + self.progress("Reset SITL commandline to default") def stop_SITL(self): self.progress("Stopping SITL")