mirror of https://github.com/ArduPilot/ardupilot
autotest: fix autotest on mac os x
This commit is contained in:
parent
a54f286c1b
commit
183e50b31f
|
@ -651,7 +651,8 @@ if __name__ == "__main__":
|
|||
''' main program '''
|
||||
os.environ['PYTHONUNBUFFERED'] = '1'
|
||||
|
||||
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
||||
if sys.platform != "darwin":
|
||||
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
||||
|
||||
class MyOptionParser(optparse.OptionParser):
|
||||
def format_epilog(self, formatter):
|
||||
|
|
|
@ -24,6 +24,10 @@ else:
|
|||
|
||||
RADIUS_OF_EARTH = 6378100.0 # in meters
|
||||
|
||||
|
||||
# List of open terminal windows for macosx
|
||||
windowID = []
|
||||
|
||||
def m2ft(x):
|
||||
"""Meters to feet."""
|
||||
return float(x) / 0.3048
|
||||
|
@ -173,6 +177,9 @@ def pexpect_close(p):
|
|||
global close_list
|
||||
|
||||
ex = None
|
||||
if p is None:
|
||||
print("Nothing to close")
|
||||
return
|
||||
try:
|
||||
p.kill(signal.SIGTERM)
|
||||
except IOError as e:
|
||||
|
@ -233,6 +240,13 @@ def kill_screen_gdb():
|
|||
cmd = ["screen", "-X", "-S", "ardupilot-gdb", "quit"]
|
||||
subprocess.Popen(cmd)
|
||||
|
||||
def kill_mac_terminal():
|
||||
global windowID
|
||||
for window in windowID:
|
||||
cmd = ("osascript -e \'tell application \"Terminal\" to close "
|
||||
"(window(get index of window id %s))\'" % window)
|
||||
os.system(cmd)
|
||||
|
||||
def start_SITL(binary,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
|
@ -291,7 +305,9 @@ def start_SITL(binary,
|
|||
f.write("disable\n")
|
||||
f.write("r\n")
|
||||
f.close()
|
||||
if os.environ.get('DISPLAY'):
|
||||
if sys.platform == "darwin" and os.getenv('DISPLAY'):
|
||||
cmd.extend(['gdb', '-x', '/tmp/x.gdb', '--args'])
|
||||
elif os.environ.get('DISPLAY'):
|
||||
cmd.extend(['xterm', '-e', 'gdb', '-x', '/tmp/x.gdb', '--args'])
|
||||
else:
|
||||
cmd.extend(['screen',
|
||||
|
@ -309,7 +325,9 @@ def start_SITL(binary,
|
|||
f.write("settings set target.process.stop-on-exec false\n")
|
||||
f.write("process launch\n")
|
||||
f.close()
|
||||
if os.environ.get('DISPLAY'):
|
||||
if sys.platform == "darwin" and os.getenv('DISPLAY'):
|
||||
cmd.extend(['lldb', '-s', '/tmp/x.lldb', '--'])
|
||||
elif os.environ.get('DISPLAY'):
|
||||
cmd.extend(['xterm', '-e', 'lldb', '-s','/tmp/x.lldb', '--'])
|
||||
else:
|
||||
raise RuntimeError("DISPLAY was not set")
|
||||
|
@ -334,7 +352,36 @@ def start_SITL(binary,
|
|||
cmd.extend(["--uartF=sim:vicon:"])
|
||||
cmd.extend(customisations)
|
||||
|
||||
if gdb and not os.getenv('DISPLAY'):
|
||||
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
|
||||
atexit.register(kill_mac_terminal)
|
||||
child = None
|
||||
mydir = os.path.dirname(os.path.realpath(__file__))
|
||||
autotest_dir = os.path.realpath(os.path.join(mydir, '..'))
|
||||
runme = [os.path.join(autotest_dir, "run_in_terminal_window.sh"), 'mactest']
|
||||
runme.extend(cmd)
|
||||
print(runme)
|
||||
print(cmd)
|
||||
out = subprocess.Popen(runme, stdout=subprocess.PIPE).communicate()[0]
|
||||
out = out.decode('utf-8')
|
||||
p = re.compile('tab 1 of window id (.*)')
|
||||
|
||||
tstart = time.time()
|
||||
while time.time() - tstart < 5:
|
||||
tabs = p.findall(out)
|
||||
|
||||
if len(tabs) > 0:
|
||||
break
|
||||
|
||||
time.sleep(0.1)
|
||||
# sleep for extra 2 seconds for application to start
|
||||
time.sleep(2)
|
||||
if len(tabs) > 0:
|
||||
windowID.append(tabs[0])
|
||||
else:
|
||||
print("Cannot find %s process terminal" % binary)
|
||||
elif gdb and not os.getenv('DISPLAY'):
|
||||
subprocess.Popen(cmd)
|
||||
atexit.register(kill_screen_gdb)
|
||||
# we are expected to return a pexpect wrapped around the
|
||||
|
@ -345,13 +392,14 @@ def start_SITL(binary,
|
|||
logfile=sys.stdout,
|
||||
encoding=ENCODING,
|
||||
timeout=5)
|
||||
else:
|
||||
print("Running: %s" % cmd_as_shell(cmd))
|
||||
|
||||
print("Running: %s" % cmd_as_shell(cmd))
|
||||
|
||||
first = cmd[0]
|
||||
rest = cmd[1:]
|
||||
child = pexpect.spawn(first, rest, logfile=sys.stdout, encoding=ENCODING, timeout=5)
|
||||
pexpect_autoclose(child)
|
||||
first = cmd[0]
|
||||
rest = cmd[1:]
|
||||
child = pexpect.spawn(first, rest, logfile=sys.stdout, encoding=ENCODING, timeout=5)
|
||||
pexpect_autoclose(child)
|
||||
# give time for parameters to properly setup
|
||||
time.sleep(3)
|
||||
if gdb or lldb:
|
||||
|
|
Loading…
Reference in New Issue