Browse Source

Tools: autotest: tee MAVProxy output to per-test file

mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
686bfc367e
  1. 6
      Tools/autotest/apmrover2.py
  2. 29
      Tools/autotest/common.py

6
Tools/autotest/apmrover2.py

@ -63,6 +63,8 @@ class AutoTestRover(AutoTest): @@ -63,6 +63,8 @@ class AutoTestRover(AutoTest):
if self.frame is None:
self.frame = 'rover'
self.mavproxy_logfile = self.open_mavproxy_logfile()
self.sitl = util.start_SITL(self.binary,
model=self.frame,
home=self.home,
@ -73,7 +75,9 @@ class AutoTestRover(AutoTest): @@ -73,7 +75,9 @@ class AutoTestRover(AutoTest):
breakpoints=self.breakpoints,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'APMrover2', options=self.mavproxy_options())
'APMrover2',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)

29
Tools/autotest/common.py

@ -109,15 +109,19 @@ class Context(object): @@ -109,15 +109,19 @@ class Context(object):
# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python
class TeeBoth(object):
def __init__(self, name, mode):
def __init__(self, name, mode, mavproxy_logfile):
self.file = open(name, mode)
self.stdout = sys.stdout
self.stderr = sys.stderr
self.mavproxy_logfile = mavproxy_logfile
self.mavproxy_logfile.set_fh(self)
sys.stdout = self
sys.stderr = self
def close(self):
sys.stdout = self.stdout
sys.stderr = self.stderr
self.mavproxy_logfile.set_fh(self)
self.mavproxy_logfile = None
self.file.close()
def write(self, data):
self.file.write(data)
@ -125,6 +129,24 @@ class TeeBoth(object): @@ -125,6 +129,24 @@ class TeeBoth(object):
def flush(self):
self.file.flush()
class MAVProxyLogFile(object):
def __init__(self):
self.fh = None
def close(self):
pass
def set_fh(self, fh):
self.fh = fh
def write(self, data):
if self.fh is not None:
self.fh.write(data)
else:
sys.stdout.write(data)
def flush(self):
if self.fh is not None:
self.fh.flush()
else:
sys.stdout.flush()
class AutoTest(ABC):
"""Base abstract class.
It implements the common function for all vehicle types.
@ -154,6 +176,9 @@ class AutoTest(ABC): @@ -154,6 +176,9 @@ class AutoTest(ABC):
def buildlogs_dirpath():
return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
def open_mavproxy_logfile(self):
return MAVProxyLogFile()
def buildlogs_path(self, path):
"""Return a string representing path in the buildlogs directory."""
bits = [self.buildlogs_dirpath()]
@ -1432,7 +1457,7 @@ class AutoTest(ABC): @@ -1432,7 +1457,7 @@ class AutoTest(ABC):
'''new-style run-one-test used by run_tests'''
test_output_filename = self.buildlogs_path("%s-%s.txt" %
(self.log_name, name))
tee = TeeBoth(test_output_filename, 'w')
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile)
prettyname = "%s (%s)" % (name, desc)
self.start_test(prettyname)

Loading…
Cancel
Save