mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
autotest: prefix all stdout from SITL binary
This commit is contained in:
parent
ddcf212c58
commit
8c5c436652
@ -400,6 +400,31 @@ class FakeMacOSXSpawn(object):
|
||||
return True
|
||||
|
||||
|
||||
class PSpawnStdPrettyPrinter(object):
|
||||
'''a fake filehandle-like object which prefixes a string to all lines
|
||||
before printing to stdout/stderr. To be used to pass to
|
||||
pexpect.spawn's logfile argument
|
||||
'''
|
||||
def __init__(self, output=sys.stdout, prefix="stdout"):
|
||||
self.output = output
|
||||
self.prefix = prefix
|
||||
self.buffer = ""
|
||||
|
||||
def close(self):
|
||||
self.print_prefixed_line(self.buffer)
|
||||
|
||||
def write(self, data):
|
||||
self.buffer += data
|
||||
for line in self.buffer.split("\n"):
|
||||
self.print_prefixed_line(line)
|
||||
|
||||
def print_prefixed_line(self, line):
|
||||
print("%s: %s" % (self.prefix, line), file=self.output)
|
||||
|
||||
def flush(self):
|
||||
pass
|
||||
|
||||
|
||||
def start_SITL(binary,
|
||||
valgrind=False,
|
||||
callgrind=False,
|
||||
@ -418,7 +443,8 @@ def start_SITL(binary,
|
||||
customisations=[],
|
||||
lldb=False,
|
||||
enable_fgview_output=False,
|
||||
supplementary=False):
|
||||
supplementary=False,
|
||||
stdout_prefix=None):
|
||||
|
||||
if model is None and not supplementary:
|
||||
raise ValueError("model must not be None")
|
||||
@ -520,6 +546,11 @@ def start_SITL(binary,
|
||||
|
||||
cmd.extend(customisations)
|
||||
|
||||
pexpect_logfile_prefix = stdout_prefix
|
||||
if pexpect_logfile_prefix is None:
|
||||
pexpect_logfile_prefix = os.path.basename(binary)
|
||||
pexpect_logfile = PSpawnStdPrettyPrinter(prefix=pexpect_logfile_prefix)
|
||||
|
||||
if (gdb or lldb) and sys.platform == "darwin" and os.getenv('DISPLAY'):
|
||||
global windowID
|
||||
# on MacOS record the window IDs so we can close them later
|
||||
@ -557,7 +588,7 @@ def start_SITL(binary,
|
||||
# AP gets a redirect-stdout-to-filehandle option. So, in the
|
||||
# meantime, return a dummy:
|
||||
return pexpect.spawn("true", ["true"],
|
||||
logfile=sys.stdout,
|
||||
logfile=pexpect_logfile,
|
||||
encoding=ENCODING,
|
||||
timeout=5)
|
||||
else:
|
||||
@ -565,7 +596,7 @@ def start_SITL(binary,
|
||||
|
||||
first = cmd[0]
|
||||
rest = cmd[1:]
|
||||
child = pexpect.spawn(first, rest, logfile=sys.stdout, encoding=ENCODING, timeout=5)
|
||||
child = pexpect.spawn(first, rest, logfile=pexpect_logfile, encoding=ENCODING, timeout=5)
|
||||
pexpect_autoclose(child)
|
||||
# give time for parameters to properly setup
|
||||
time.sleep(3)
|
||||
|
Loading…
Reference in New Issue
Block a user