mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
autotest: replace sitl_32bit with force_32bit
This commit is contained in:
parent
50bfa516bc
commit
c90cf03619
@ -444,7 +444,7 @@ def run_step(step):
|
|||||||
"postype_single": opts.postype_single,
|
"postype_single": opts.postype_single,
|
||||||
"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,
|
"force_32bit" : opts.force_32bit,
|
||||||
"ubsan" : opts.ubsan,
|
"ubsan" : opts.ubsan,
|
||||||
"ubsan_abort" : opts.ubsan_abort,
|
"ubsan_abort" : opts.ubsan_abort,
|
||||||
"num_aux_imus" : opts.num_aux_imus,
|
"num_aux_imus" : opts.num_aux_imus,
|
||||||
@ -958,10 +958,10 @@ if __name__ == "__main__":
|
|||||||
action="store_true",
|
action="store_true",
|
||||||
dest="ekf_single",
|
dest="ekf_single",
|
||||||
help="force single precision EKF")
|
help="force single precision EKF")
|
||||||
group_build.add_option("--sitl-32bit",
|
group_build.add_option("--force-32bit",
|
||||||
default=False,
|
default=False,
|
||||||
action='store_true',
|
action='store_true',
|
||||||
dest="sitl_32bit",
|
dest="force_32bit",
|
||||||
help="compile sitl using 32-bit")
|
help="compile sitl using 32-bit")
|
||||||
group_build.add_option("", "--ubsan",
|
group_build.add_option("", "--ubsan",
|
||||||
default=False,
|
default=False,
|
||||||
|
@ -1494,7 +1494,7 @@ class AutoTest(ABC):
|
|||||||
replay=False,
|
replay=False,
|
||||||
sup_binaries=[],
|
sup_binaries=[],
|
||||||
reset_after_every_test=False,
|
reset_after_every_test=False,
|
||||||
sitl_32bit=False,
|
force_32bit=False,
|
||||||
ubsan=False,
|
ubsan=False,
|
||||||
ubsan_abort=False,
|
ubsan_abort=False,
|
||||||
num_aux_imus=0,
|
num_aux_imus=0,
|
||||||
@ -1521,7 +1521,7 @@ class AutoTest(ABC):
|
|||||||
self.speedup = self.default_speedup()
|
self.speedup = self.default_speedup()
|
||||||
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.force_32bit = force_32bit
|
||||||
self.ubsan = ubsan
|
self.ubsan = ubsan
|
||||||
self.ubsan_abort = ubsan_abort
|
self.ubsan_abort = ubsan_abort
|
||||||
self.build_opts = build_opts
|
self.build_opts = build_opts
|
||||||
|
@ -112,7 +112,7 @@ def waf_configure(board,
|
|||||||
coverage=False,
|
coverage=False,
|
||||||
ekf_single=False,
|
ekf_single=False,
|
||||||
postype_single=False,
|
postype_single=False,
|
||||||
sitl_32bit=False,
|
force_32bit=False,
|
||||||
extra_args=[],
|
extra_args=[],
|
||||||
extra_hwdef=None,
|
extra_hwdef=None,
|
||||||
ubsan=False,
|
ubsan=False,
|
||||||
@ -130,8 +130,8 @@ def waf_configure(board,
|
|||||||
cmd_configure.append('--ekf-single')
|
cmd_configure.append('--ekf-single')
|
||||||
if postype_single:
|
if postype_single:
|
||||||
cmd_configure.append('--postype-single')
|
cmd_configure.append('--postype-single')
|
||||||
if sitl_32bit:
|
if force_32bit:
|
||||||
cmd_configure.append('--sitl-32bit')
|
cmd_configure.append('--force-32bit')
|
||||||
if ubsan:
|
if ubsan:
|
||||||
cmd_configure.append('--ubsan')
|
cmd_configure.append('--ubsan')
|
||||||
if ubsan_abort:
|
if ubsan_abort:
|
||||||
@ -174,7 +174,7 @@ def build_SITL(
|
|||||||
j=None,
|
j=None,
|
||||||
math_check_indexes=False,
|
math_check_indexes=False,
|
||||||
postype_single=False,
|
postype_single=False,
|
||||||
sitl_32bit=False,
|
force_32bit=False,
|
||||||
ubsan=False,
|
ubsan=False,
|
||||||
ubsan_abort=False,
|
ubsan_abort=False,
|
||||||
num_aux_imus=0,
|
num_aux_imus=0,
|
||||||
@ -189,7 +189,7 @@ def build_SITL(
|
|||||||
ekf_single=ekf_single,
|
ekf_single=ekf_single,
|
||||||
postype_single=postype_single,
|
postype_single=postype_single,
|
||||||
coverage=coverage,
|
coverage=coverage,
|
||||||
sitl_32bit=sitl_32bit,
|
force_32bit=force_32bit,
|
||||||
ubsan=ubsan,
|
ubsan=ubsan,
|
||||||
ubsan_abort=ubsan_abort,
|
ubsan_abort=ubsan_abort,
|
||||||
extra_defines=extra_defines,
|
extra_defines=extra_defines,
|
||||||
@ -209,7 +209,7 @@ def build_SITL(
|
|||||||
|
|
||||||
|
|
||||||
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, ubsan=False, ubsan_abort=False, num_aux_imus=0,
|
ekf_single=False, postype_single=False, force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0,
|
||||||
extra_configure_args=[]):
|
extra_configure_args=[]):
|
||||||
# first configure
|
# first configure
|
||||||
if configure:
|
if configure:
|
||||||
@ -220,7 +220,7 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math
|
|||||||
ekf_single=ekf_single,
|
ekf_single=ekf_single,
|
||||||
postype_single=postype_single,
|
postype_single=postype_single,
|
||||||
coverage=coverage,
|
coverage=coverage,
|
||||||
sitl_32bit=sitl_32bit,
|
force_32bit=force_32bit,
|
||||||
ubsan=ubsan,
|
ubsan=ubsan,
|
||||||
ubsan_abort=ubsan_abort,
|
ubsan_abort=ubsan_abort,
|
||||||
extra_args=extra_configure_args)
|
extra_args=extra_configure_args)
|
||||||
@ -258,7 +258,7 @@ def build_tests(board,
|
|||||||
coverage=False,
|
coverage=False,
|
||||||
ekf_single=False,
|
ekf_single=False,
|
||||||
postype_single=False,
|
postype_single=False,
|
||||||
sitl_32bit=False,
|
force_32bit=False,
|
||||||
ubsan=False,
|
ubsan=False,
|
||||||
ubsan_abort=False,
|
ubsan_abort=False,
|
||||||
num_aux_imus=0,
|
num_aux_imus=0,
|
||||||
@ -273,7 +273,7 @@ def build_tests(board,
|
|||||||
ekf_single=ekf_single,
|
ekf_single=ekf_single,
|
||||||
postype_single=postype_single,
|
postype_single=postype_single,
|
||||||
coverage=coverage,
|
coverage=coverage,
|
||||||
sitl_32bit=sitl_32bit,
|
force_32bit=force_32bit,
|
||||||
ubsan=ubsan,
|
ubsan=ubsan,
|
||||||
ubsan_abort=ubsan_abort,
|
ubsan_abort=ubsan_abort,
|
||||||
extra_args=extra_configure_args)
|
extra_args=extra_configure_args)
|
||||||
|
@ -393,8 +393,8 @@ def do_build(opts, frame_options):
|
|||||||
if opts.ekf_single:
|
if opts.ekf_single:
|
||||||
cmd_configure.append("--ekf-single")
|
cmd_configure.append("--ekf-single")
|
||||||
|
|
||||||
if opts.sitl_32bit:
|
if opts.force_32bit:
|
||||||
cmd_configure.append("--sitl-32bit")
|
cmd_configure.append("--force-32bit")
|
||||||
|
|
||||||
if opts.ubsan:
|
if opts.ubsan:
|
||||||
cmd_configure.append("--ubsan")
|
cmd_configure.append("--ubsan")
|
||||||
@ -1029,10 +1029,10 @@ group_build.add_option("--enable-math-check-indexes",
|
|||||||
action="store_true",
|
action="store_true",
|
||||||
dest="math_check_indexes",
|
dest="math_check_indexes",
|
||||||
help="enable checking of math indexes")
|
help="enable checking of math indexes")
|
||||||
group_build.add_option("", "--sitl-32bit",
|
group_build.add_option("", "--force-32bit",
|
||||||
default=False,
|
default=False,
|
||||||
action='store_true',
|
action='store_true',
|
||||||
dest="sitl_32bit",
|
dest="force_32bit",
|
||||||
help="compile sitl using 32-bit")
|
help="compile sitl using 32-bit")
|
||||||
group_build.add_option("", "--configure-define",
|
group_build.add_option("", "--configure-define",
|
||||||
default=[],
|
default=[],
|
||||||
|
Loading…
Reference in New Issue
Block a user