Browse Source

autotest: added --ubsan and --ubsan-abort to sim_vehicle.py and autotest.py

allows for undefined behaviour checking in SITL
apm_2208
Andrew Tridgell 3 years ago
parent
commit
2f7a8769c0
  1. 12
      Tools/autotest/autotest.py
  2. 6
      Tools/autotest/common.py
  3. 18
      Tools/autotest/pysim/util.py
  4. 16
      Tools/autotest/sim_vehicle.py

12
Tools/autotest/autotest.py

@ -447,6 +447,8 @@ def run_step(step):
"extra_configure_args": opts.waf_configure_args, "extra_configure_args": opts.waf_configure_args,
"coverage": opts.coverage, "coverage": opts.coverage,
"sitl_32bit" : opts.sitl_32bit, "sitl_32bit" : opts.sitl_32bit,
"ubsan" : opts.ubsan,
"ubsan_abort" : opts.ubsan_abort,
} }
if opts.Werror: if opts.Werror:
@ -959,6 +961,16 @@ if __name__ == "__main__":
action='store_true', action='store_true',
dest="sitl_32bit", dest="sitl_32bit",
help="compile sitl using 32-bit") help="compile sitl using 32-bit")
group_build.add_option("", "--ubsan",
default=False,
action='store_true',
dest="ubsan",
help="compile sitl with undefined behaviour sanitiser")
group_build.add_option("", "--ubsan-abort",
default=False,
action='store_true',
dest="ubsan_abort",
help="compile sitl with undefined behaviour sanitiser and abort on error")
parser.add_option_group(group_build) parser.add_option_group(group_build)
group_sim = optparse.OptionGroup(parser, "Simulation options") group_sim = optparse.OptionGroup(parser, "Simulation options")

6
Tools/autotest/common.py

@ -1465,7 +1465,9 @@ class AutoTest(ABC):
replay=False, replay=False,
sup_binaries=[], sup_binaries=[],
reset_after_every_test=False, reset_after_every_test=False,
sitl_32bit=False): sitl_32bit=False,
ubsan=False,
ubsan_abort=False):
self.start_time = time.time() self.start_time = time.time()
global __autotest__ # FIXME; make progress a non-staticmethod global __autotest__ # FIXME; make progress a non-staticmethod
@ -1491,6 +1493,8 @@ class AutoTest(ABC):
self.sup_binaries = sup_binaries self.sup_binaries = sup_binaries
self.reset_after_every_test = reset_after_every_test self.reset_after_every_test = reset_after_every_test
self.sitl_32bit = sitl_32bit self.sitl_32bit = sitl_32bit
self.ubsan = ubsan
self.ubsan_abort = ubsan_abort
self.mavproxy = None self.mavproxy = None
self._mavproxy = None # for auto-cleanup on failed tests self._mavproxy = None # for auto-cleanup on failed tests

18
Tools/autotest/pysim/util.py

@ -99,7 +99,7 @@ def relwaf():
return "./modules/waf/waf-light" return "./modules/waf/waf-light"
def waf_configure(board, j=None, debug=False, math_check_indexes=False, coverage=False, ekf_single=False, postype_single=False, sitl_32bit=False, extra_args=[], extra_hwdef=None): def waf_configure(board, j=None, debug=False, math_check_indexes=False, coverage=False, ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, extra_args=[], extra_hwdef=None):
cmd_configure = [relwaf(), "configure", "--board", board] cmd_configure = [relwaf(), "configure", "--board", board]
if debug: if debug:
cmd_configure.append('--debug') cmd_configure.append('--debug')
@ -113,6 +113,10 @@ def waf_configure(board, j=None, debug=False, math_check_indexes=False, coverage
cmd_configure.append('--postype-single') cmd_configure.append('--postype-single')
if sitl_32bit: if sitl_32bit:
cmd_configure.append('--sitl-32bit') cmd_configure.append('--sitl-32bit')
if ubsan:
cmd_configure.append('--ubsan')
if ubsan_abort:
cmd_configure.append('--ubsan-abort')
if extra_hwdef is not None: if extra_hwdef is not None:
cmd_configure.extend(['--extra-hwdef', extra_hwdef]) cmd_configure.extend(['--extra-hwdef', extra_hwdef])
if j is not None: if j is not None:
@ -134,7 +138,7 @@ def waf_build(target=None):
run_cmd(cmd, directory=topdir(), checkfail=True) run_cmd(cmd, directory=topdir(), checkfail=True)
def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, configure=True, math_check_indexes=False, coverage=False, def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, configure=True, math_check_indexes=False, coverage=False,
ekf_single=False, postype_single=False, sitl_32bit=False, extra_configure_args=[]): ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, extra_configure_args=[]):
# first configure # first configure
if configure: if configure:
@ -146,6 +150,8 @@ def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, conf
postype_single=postype_single, postype_single=postype_single,
coverage=coverage, coverage=coverage,
sitl_32bit=sitl_32bit, sitl_32bit=sitl_32bit,
ubsan=ubsan,
ubsan_abort=ubsan_abort,
extra_args=extra_configure_args) extra_args=extra_configure_args)
# then clean # then clean
@ -161,7 +167,7 @@ def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, conf
def build_examples(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, def build_examples(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False,
ekf_single=False, postype_single=False, sitl_32bit=False, ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False,
extra_configure_args=[]): extra_configure_args=[]):
# first configure # first configure
if configure: if configure:
@ -173,6 +179,8 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math
postype_single=postype_single, postype_single=postype_single,
coverage=coverage, coverage=coverage,
sitl_32bit=sitl_32bit, sitl_32bit=sitl_32bit,
ubsan=ubsan,
ubsan_abort=ubsan_abort,
extra_args=extra_configure_args) extra_args=extra_configure_args)
# then clean # then clean
@ -198,7 +206,7 @@ def build_replay(board, j=None, debug=False, clean=False):
return True return True
def build_tests(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, def build_tests(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False,
ekf_single=False, postype_single=False, sitl_32bit=False, extra_configure_args=[]): ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, extra_configure_args=[]):
# first configure # first configure
if configure: if configure:
@ -210,6 +218,8 @@ def build_tests(board, j=None, debug=False, clean=False, configure=True, math_ch
postype_single=postype_single, postype_single=postype_single,
coverage=coverage, coverage=coverage,
sitl_32bit=sitl_32bit, sitl_32bit=sitl_32bit,
ubsan=ubsan,
ubsan_abort=ubsan_abort,
extra_args=extra_configure_args) extra_args=extra_configure_args)
# then clean # then clean

16
Tools/autotest/sim_vehicle.py

@ -364,6 +364,12 @@ def do_build(opts, frame_options):
if opts.sitl_32bit: if opts.sitl_32bit:
cmd_configure.append("--sitl-32bit") cmd_configure.append("--sitl-32bit")
if opts.ubsan:
cmd_configure.append("--ubsan")
if opts.ubsan_abort:
cmd_configure.append("--ubsan-abort")
pieces = [shlex.split(x) for x in opts.waf_configure_args] pieces = [shlex.split(x) for x in opts.waf_configure_args]
for piece in pieces: for piece in pieces:
cmd_configure.extend(piece) cmd_configure.extend(piece)
@ -982,6 +988,16 @@ group_build.add_option("", "--coverage",
action='store_true', action='store_true',
default=False, default=False,
help="use coverage build") help="use coverage build")
group_build.add_option("", "--ubsan",
default=False,
action='store_true',
dest="ubsan",
help="compile sitl with undefined behaviour sanitiser")
group_build.add_option("", "--ubsan-abort",
default=False,
action='store_true',
dest="ubsan_abort",
help="compile sitl with undefined behaviour sanitiser and abort on error")
parser.add_option_group(group_build) parser.add_option_group(group_build)
group_sim = optparse.OptionGroup(parser, "Simulation options") group_sim = optparse.OptionGroup(parser, "Simulation options")

Loading…
Cancel
Save