Tools: autotest: check we're seeing PL messages in the log during

precland
This commit is contained in:
Peter Barker 2019-04-03 13:53:56 +11:00 committed by Andrew Tridgell
parent ade6281923
commit 696de42eea
2 changed files with 25 additions and 2 deletions

View File

@ -1698,8 +1698,11 @@ class AutoTestCopter(AutoTest):
if delta > max_delta:
raise NotAchievedException("Did not land close enough to original position (%fm > %fm" % (delta, max_delta))
if not self.current_onboard_log_contains_message("PL"):
raise NotAchievedException("Did not see expected PL message")
except Exception as e:
self.progress("Exception caught")
self.progress("Exception caught (%s)" % str(e))
ex = e
self.zero_throttle()

View File

@ -13,7 +13,7 @@ import pexpect
import fnmatch
import operator
from pymavlink import mavwp, mavutil
from pymavlink import mavwp, mavutil, DFReader
from pysim import util, vehicleinfo
# a list of pexpect objects to read while waiting for
@ -2532,6 +2532,26 @@ switch value'''
self.progress("##### %s is skipped: %s" % (name, reason))
self.skip_list.append((test, reason))
def last_onboard_log(self):
'''return number of last onboard log'''
self.mavproxy.send("log list\n")
self.mavproxy.expect("lastLog ([0-9]+)")
return int(self.mavproxy.match.group(1))
def current_onboard_log_filepath(self):
'''return filepath to currently open dataflash log'''
return os.path.join("logs/%08u.BIN" % self.last_onboard_log())
def dfreader_for_current_onboard_log(self):
return DFReader.DFReader_binary(self.current_onboard_log_filepath(),
zero_time_base=True);
def current_onboard_log_contains_message(self, messagetype):
dfreader = self.dfreader_for_current_onboard_log()
m = dfreader.recv_match(type=messagetype)
print("m=%s" % str(m))
return m is not None
def run_tests(self, tests):
"""Autotest vehicle in SITL."""
if self.run_tests_called: