autotest: add support for setting number of auxiliary IMUs

This commit is contained in:
bugobliterator 2023-03-04 10:53:50 +11:00 committed by Andrew Tridgell
parent 14ae431056
commit e2509b7c6b
4 changed files with 91 additions and 2 deletions

View File

@ -447,6 +447,7 @@ def run_step(step):
"sitl_32bit" : opts.sitl_32bit,
"ubsan" : opts.ubsan,
"ubsan_abort" : opts.ubsan_abort,
"num_aux_imus" : opts.num_aux_imus,
}
if opts.Werror:
@ -529,6 +530,7 @@ def run_step(step):
"frame": opts.frame,
"_show_test_timings": opts.show_test_timings,
"force_ahrs_type": opts.force_ahrs_type,
"num_aux_imus" : opts.num_aux_imus,
"replay": opts.replay,
"logs_dir": buildlogs_dirpath(),
"sup_binaries": supplementary_binaries,
@ -971,6 +973,11 @@ if __name__ == "__main__":
action='store_true',
dest="ubsan_abort",
help="compile sitl with undefined behaviour sanitiser and abort on error")
group_build.add_option("--num-aux-imus",
dest="num_aux_imus",
default=0,
type='int',
help='number of auxiliary IMUs to simulate')
parser.add_option_group(group_build)
group_sim = optparse.OptionGroup(parser, "Simulation options")

View File

@ -1497,6 +1497,7 @@ class AutoTest(ABC):
sitl_32bit=False,
ubsan=False,
ubsan_abort=False,
num_aux_imus=0,
build_opts={}):
self.start_time = time.time()
@ -1524,6 +1525,7 @@ class AutoTest(ABC):
self.ubsan = ubsan
self.ubsan_abort = ubsan_abort
self.build_opts = build_opts
self.num_aux_imus = num_aux_imus
self.mavproxy = None
self._mavproxy = None # for auto-cleanup on failed tests
@ -2149,6 +2151,20 @@ class AutoTest(ABC):
"SIM_ACC3_SCAL_X",
"SIM_ACC3_SCAL_Y",
"SIM_ACC3_SCAL_Z",
"SIM_ACC4_RND",
"SIM_ACC4_SCAL_X",
"SIM_ACC4_SCAL_Y",
"SIM_ACC4_SCAL_Z",
"SIM_ACC4_BIAS_X",
"SIM_ACC4_BIAS_Y",
"SIM_ACC4_BIAS_Z",
"SIM_ACC5_RND",
"SIM_ACC5_SCAL_X",
"SIM_ACC5_SCAL_Y",
"SIM_ACC5_SCAL_Z",
"SIM_ACC5_BIAS_X",
"SIM_ACC5_BIAS_Y",
"SIM_ACC5_BIAS_Z",
"SIM_ACC_FILE_RW",
"SIM_ACC_TRIM_X",
"SIM_ACC_TRIM_Y",
@ -2273,6 +2289,14 @@ class AutoTest(ABC):
"SIM_GYR3_SCALE_X",
"SIM_GYR3_SCALE_Y",
"SIM_GYR3_SCALE_Z",
"SIM_GYR4_RND",
"SIM_GYR4_SCALE_X",
"SIM_GYR4_SCALE_Y",
"SIM_GYR4_SCALE_Z",
"SIM_GYR5_RND",
"SIM_GYR5_SCALE_X",
"SIM_GYR5_SCALE_Y",
"SIM_GYR5_SCALE_Z",
"SIM_GYR_FAIL_MSK",
"SIM_GYR_FILE_RW",
"SIM_IE24_ENABLE",
@ -2345,6 +2369,48 @@ class AutoTest(ABC):
"SIM_IMUT3_GYR3_Z",
"SIM_IMUT3_TMAX",
"SIM_IMUT3_TMIN",
"SIM_IMUT4_ACC1_X",
"SIM_IMUT4_ACC1_Y",
"SIM_IMUT4_ACC1_Z",
"SIM_IMUT4_ACC2_X",
"SIM_IMUT4_ACC2_Y",
"SIM_IMUT4_ACC2_Z",
"SIM_IMUT4_ACC3_X",
"SIM_IMUT4_ACC3_Y",
"SIM_IMUT4_ACC3_Z",
"SIM_IMUT4_ENABLE",
"SIM_IMUT4_GYR1_X",
"SIM_IMUT4_GYR1_Y",
"SIM_IMUT4_GYR1_Z",
"SIM_IMUT4_GYR2_X",
"SIM_IMUT4_GYR2_Y",
"SIM_IMUT4_GYR2_Z",
"SIM_IMUT4_GYR3_X",
"SIM_IMUT4_GYR3_Y",
"SIM_IMUT4_GYR3_Z",
"SIM_IMUT4_TMAX",
"SIM_IMUT4_TMIN",
"SIM_IMUT5_ACC1_X",
"SIM_IMUT5_ACC1_Y",
"SIM_IMUT5_ACC1_Z",
"SIM_IMUT5_ACC2_X",
"SIM_IMUT5_ACC2_Y",
"SIM_IMUT5_ACC2_Z",
"SIM_IMUT5_ACC3_X",
"SIM_IMUT5_ACC3_Y",
"SIM_IMUT5_ACC3_Z",
"SIM_IMUT5_ENABLE",
"SIM_IMUT5_GYR1_X",
"SIM_IMUT5_GYR1_Y",
"SIM_IMUT5_GYR1_Z",
"SIM_IMUT5_GYR2_X",
"SIM_IMUT5_GYR2_Y",
"SIM_IMUT5_GYR2_Z",
"SIM_IMUT5_GYR3_X",
"SIM_IMUT5_GYR3_Y",
"SIM_IMUT5_GYR3_Z",
"SIM_IMUT5_TMAX",
"SIM_IMUT5_TMIN",
"SIM_IMUT_END",
"SIM_IMUT_FIXED",
"SIM_IMUT_START",
@ -3006,6 +3072,8 @@ class AutoTest(ABC):
if self.force_ahrs_type == 3:
ret["EK3_ENABLE"] = 1
ret["AHRS_EKF_TYPE"] = self.force_ahrs_type
if self.num_aux_imus > 0:
ret["SIM_IMU_COUNT"] = self.num_aux_imus + 3
if self.replay:
ret["LOG_REPLAY"] = 1
return ret

View File

@ -117,6 +117,7 @@ def waf_configure(board,
extra_hwdef=None,
ubsan=False,
ubsan_abort=False,
num_aux_imus=0,
extra_defines={}):
cmd_configure = [relwaf(), "configure", "--board", board]
if debug:
@ -135,6 +136,8 @@ def waf_configure(board,
cmd_configure.append('--ubsan')
if ubsan_abort:
cmd_configure.append('--ubsan-abort')
if num_aux_imus > 0:
cmd_configure.append('--num-aux-imus=%u' % num_aux_imus)
if extra_hwdef is not None:
cmd_configure.extend(['--extra-hwdef', extra_hwdef])
for nv in extra_defines.items():
@ -174,6 +177,7 @@ def build_SITL(
sitl_32bit=False,
ubsan=False,
ubsan_abort=False,
num_aux_imus=0,
):
# first configure
@ -189,7 +193,8 @@ def build_SITL(
ubsan=ubsan,
ubsan_abort=ubsan_abort,
extra_defines=extra_defines,
extra_args=extra_configure_args)
num_aux_imus=num_aux_imus,
extra_args=extra_configure_args,)
# then clean
if clean:
@ -204,7 +209,7 @@ def build_SITL(
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,
ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0,
extra_configure_args=[]):
# first configure
if configure:
@ -256,6 +261,7 @@ def build_tests(board,
sitl_32bit=False,
ubsan=False,
ubsan_abort=False,
num_aux_imus=0,
extra_configure_args=[]):
# first configure

View File

@ -402,6 +402,9 @@ def do_build(opts, frame_options):
if opts.ubsan_abort:
cmd_configure.append("--ubsan-abort")
if opts.num_aux_imus:
cmd_configure.append("--num-aux-imus=%s" % opts.num_aux_imus)
for nv in opts.define:
cmd_configure.append("--define=%s" % nv)
@ -1064,6 +1067,11 @@ group_build.add_option("", "--ubsan-abort",
action='store_true',
dest="ubsan_abort",
help="compile sitl with undefined behaviour sanitiser and abort on error")
group_build.add_option("--num-aux-imus",
dest="num_aux_imus",
default=0,
type='int',
help='number of auxiliary IMUs to simulate')
parser.add_option_group(group_build)
group_sim = optparse.OptionGroup(parser, "Simulation options")