Tools: add ability for autotest to run examples
This commit is contained in:
parent
220a3d19bf
commit
4023f847c8
@ -23,6 +23,7 @@ import ardusub
|
||||
import quadplane
|
||||
import balancebot
|
||||
|
||||
import examples
|
||||
from pysim import util
|
||||
from pymavlink import mavutil
|
||||
from pymavlink.generator import mavtemplate
|
||||
@ -131,7 +132,7 @@ def build_devrelease():
|
||||
|
||||
def build_examples():
|
||||
"""Build examples."""
|
||||
for target in 'px4-v2', 'navio':
|
||||
for target in 'fmuv2', 'px4-v2', 'navio', 'linux':
|
||||
print("Running build.examples for %s" % target)
|
||||
try:
|
||||
util.build_examples(target)
|
||||
@ -390,9 +391,12 @@ def run_step(step):
|
||||
if step == 'build.DevRelease':
|
||||
return build_devrelease()
|
||||
|
||||
if step == 'build.Examples':
|
||||
if step == 'build.examples':
|
||||
return build_examples()
|
||||
|
||||
if step == 'run.examples':
|
||||
return examples.run_examples(debug=opts.debug, valgrind=False, gdb=False)
|
||||
|
||||
if step == 'build.Parameters':
|
||||
return build_parameters()
|
||||
|
||||
@ -665,11 +669,12 @@ if __name__ == "__main__":
|
||||
'build.All',
|
||||
'build.Binaries',
|
||||
# 'build.DevRelease',
|
||||
'build.Examples',
|
||||
'build.Parameters',
|
||||
|
||||
'build.unit_tests',
|
||||
'run.unit_tests',
|
||||
'build.examples',
|
||||
'run.examples',
|
||||
|
||||
'build.ArduPlane',
|
||||
'defaults.ArduPlane',
|
||||
|
43
Tools/autotest/examples.py
Normal file
43
Tools/autotest/examples.py
Normal file
@ -0,0 +1,43 @@
|
||||
from __future__ import print_function
|
||||
|
||||
import os
|
||||
import subprocess
|
||||
import time
|
||||
|
||||
from pysim import util
|
||||
|
||||
def run_example(filepath, valgrind=False, gdb=False):
|
||||
cmd = []
|
||||
if valgrind:
|
||||
cmd.append("valgrind")
|
||||
if gdb:
|
||||
cmd.append("gdb")
|
||||
cmd.append(filepath)
|
||||
print("Running: (%s)" % str(cmd))
|
||||
bob = subprocess.Popen(cmd, stdin=None, close_fds=True)
|
||||
time.sleep(10)
|
||||
bob.kill()
|
||||
bob.wait()
|
||||
if bob.returncode is None:
|
||||
raise ValueError("Unable to kill subprocess")
|
||||
print("returncode: %u" % (bob.returncode))
|
||||
if bob.returncode != -9:
|
||||
raise ValueError("Process exitted before I got to kill it (exit code=%u)" % bob.returncode)
|
||||
print("returncode2: %u" % (bob.returncode))
|
||||
|
||||
def run_examples(debug=False, valgrind=False, gdb=False):
|
||||
dirpath = util.reltopdir(os.path.join('build', 'linux', 'examples'))
|
||||
|
||||
skip = {
|
||||
"BARO_generic": "Most linux computers don't have baros...",
|
||||
}
|
||||
for afile in os.listdir(dirpath):
|
||||
if afile in skip:
|
||||
print("Skipping %s: %s" % (afile, skip[afile]))
|
||||
continue
|
||||
filepath = os.path.join(dirpath, afile)
|
||||
if not os.path.isfile(filepath):
|
||||
continue
|
||||
run_example(filepath, valgrind=valgrind, gdb=gdb)
|
||||
|
||||
return True
|
Loading…
Reference in New Issue
Block a user