autotest: fix SYSTEM_TIME stream detection function

MAVProxy's output is read by autotest via pexpect.

SITL's output is read by MAVProxy.

If we don't read MAVProxy's stdout then it doesn't read SITL and
everything stops.

Also, since we need to drain pexpects as part of reboot, and applying
parameter files requires rebooting... we need to append the expect
objects to the global list before we apply parameter files.  So move
that call.
This commit is contained in:
Peter Barker 2020-06-10 15:42:53 +10:00 committed by Peter Barker
parent c1403a2e2b
commit e207bbdf2a

View File

@ -979,15 +979,18 @@ class AutoTest(ABC):
self.initialise_after_reboot_sitl() self.initialise_after_reboot_sitl()
def set_streamrate(self, streamrate): def set_streamrate(self, streamrate, timeout=10):
tstart = time.time() tstart = time.time()
while True: while True:
if time.time() - tstart > 10: if time.time() - tstart > timeout:
raise AutoTestTimeoutException("stream rate change failed") raise AutoTestTimeoutException("stream rate change failed")
self.mavproxy.send("set streamrate %u\n" % (streamrate)) self.mavproxy.send("set streamrate %u\n" % (streamrate))
self.mavproxy.send("set streamrate\n") self.mavproxy.send("set streamrate\n")
self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1) try:
self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1)
except pexpect.TIMEOUT:
continue
rate = self.mavproxy.match.group(1) rate = self.mavproxy.match.group(1)
print("rate: %s" % str(rate)) print("rate: %s" % str(rate))
if int(rate) == int(streamrate): if int(rate) == int(streamrate):
@ -996,13 +999,20 @@ class AutoTest(ABC):
if streamrate <= 0: if streamrate <= 0:
return return
self.drain_mav() self.progress("Waiting for SYSTEM_TIME for confirmation streams are working")
m = self.mav.recv_match(type='SYSTEM_TIME', self.drain_mav_unparsed()
blocking=True, timeout = 60
timeout=10) tstart = time.time()
print("Received (%s)" % str(m)) while True:
if m is None: self.drain_all_pexpects()
raise NotAchievedException("Did not get SYSTEM_TIME") if time.time() - tstart > timeout:
raise NotAchievedException("Did not get SYSTEM_TIME within %f seconds" % timeout)
m = self.mav.recv_match(timeout=0.1)
if m is None:
continue
# self.progress("Received (%s)" % str(m))
if m.get_type() == 'SYSTEM_TIME':
break
self.drain_mav() self.drain_mav()
def htree_from_xml(self, xml_filepath): def htree_from_xml(self, xml_filepath):
@ -1786,7 +1796,7 @@ class AutoTest(ABC):
"""Get SITL time in seconds.""" """Get SITL time in seconds."""
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=timeout) m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=timeout)
if m is None: if m is None:
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message") raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)
return m.time_boot_ms * 1.0e-3 return m.time_boot_ms * 1.0e-3
def get_sim_time_cached(self): def get_sim_time_cached(self):
@ -3953,13 +3963,13 @@ class AutoTest(ABC):
self.progress("Starting MAVLink connection") self.progress("Starting MAVLink connection")
self.get_mavlink_connection_going() self.get_mavlink_connection_going()
self.apply_defaultfile_parameters()
util.expect_setup_callback(self.mavproxy, self.expect_callback) util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear() self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy]) self.expect_list_extend([self.sitl, self.mavproxy])
self.apply_defaultfile_parameters()
self.progress("Ready to start testing!") self.progress("Ready to start testing!")
def upload_using_mission_protocol(self, mission_type, items): def upload_using_mission_protocol(self, mission_type, items):