autotest: mark stdout unbuffered
this makes the logs easier to read
This commit is contained in:
parent
4877892d6e
commit
5fd04e0c23
@ -6,6 +6,8 @@ import pexpect, os, util, sys, shutil
|
|||||||
import arducopter, arduplane
|
import arducopter, arduplane
|
||||||
import optparse, fnmatch, time, glob, traceback
|
import optparse, fnmatch, time, glob, traceback
|
||||||
|
|
||||||
|
os.environ['PYTHONUNBUFFERED'] = '1'
|
||||||
|
|
||||||
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
||||||
|
|
||||||
def get_default_params(atype):
|
def get_default_params(atype):
|
||||||
@ -241,7 +243,7 @@ def run_tests(steps):
|
|||||||
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
|
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
|
||||||
traceback.print_exc(file=sys.stdout)
|
traceback.print_exc(file=sys.stdout)
|
||||||
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
|
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
|
||||||
pass
|
continue
|
||||||
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
|
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
|
||||||
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
|
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
|
||||||
if not passed:
|
if not passed:
|
||||||
|
Loading…
Reference in New Issue
Block a user