mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
autotest: cope with exceptions in tests leaving child processes
This commit is contained in:
parent
0e8a17f645
commit
7a201233c0
@ -14,6 +14,7 @@ def get_default_params(atype):
|
||||
'''get default parameters'''
|
||||
sil = util.start_SIL(atype, wipe=True)
|
||||
mavproxy = util.start_MAVProxy_SIL(atype)
|
||||
print("Dumping defaults")
|
||||
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
|
||||
if idx == 0:
|
||||
# we need to restart it after eeprom erase
|
||||
@ -37,11 +38,15 @@ def dump_logs(atype):
|
||||
logfile = util.reltopdir('../buildlogs/%s.flashlog' % atype)
|
||||
log = open(logfile, mode='w')
|
||||
mavproxy = util.start_MAVProxy_SIL(atype, setup=True, logfile=log)
|
||||
print("navigating menus")
|
||||
mavproxy.expect(']')
|
||||
mavproxy.send("logs\n")
|
||||
mavproxy.expect("logs enabled:")
|
||||
mavproxy.expect("(\d+) logs")
|
||||
numlogs = int(mavproxy.match.group(1))
|
||||
i = mavproxy.expect(["No logs", "(\d+) logs"])
|
||||
if i == 0:
|
||||
numlogs = 0
|
||||
else:
|
||||
numlogs = int(mavproxy.match.group(1))
|
||||
mavproxy.expect("Log]")
|
||||
for i in range(numlogs):
|
||||
mavproxy.send("dump %u\n" % (i+1))
|
||||
@ -243,6 +248,7 @@ def run_tests(steps):
|
||||
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
|
||||
traceback.print_exc(file=sys.stdout)
|
||||
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
|
||||
util.pexpect_close_all()
|
||||
continue
|
||||
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
|
||||
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
|
||||
|
Loading…
Reference in New Issue
Block a user