mirror of https://github.com/ArduPilot/ardupilot
autotest: implement parameter files per peripheral in CI tests
this allows for one peripheral to have ESCs and the other not
This commit is contained in:
parent
5f47a94e2b
commit
6643231b2e
|
@ -2620,8 +2620,23 @@ class AutoTestCopter(AutoTest):
|
|||
"CAN_P1_DRIVER": 1,
|
||||
"GPS_TYPE": 9,
|
||||
"GPS_TYPE2": 9,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_SPEEDUP": 5,
|
||||
# disable simulated GPS, so only via DroneCAN
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS2_DISABLE": 1,
|
||||
# this ensures we use DroneCAN baro and compass
|
||||
"SIM_BARO_COUNT" : 0,
|
||||
"SIM_MAG1_DEVID" : 0,
|
||||
"SIM_MAG2_DEVID" : 0,
|
||||
"SIM_MAG3_DEVID" : 0,
|
||||
"COMPASS_USE2" : 0,
|
||||
"COMPASS_USE3" : 0,
|
||||
# use DroneCAN rangefinder
|
||||
"RNGFND1_TYPE" : 24,
|
||||
"RNGFND1_MAX_CM" : 11000,
|
||||
# use DroneCAN battery monitoring, and enforce with a arming voltage
|
||||
"BATT_MONITOR" : 8,
|
||||
"BATT_ARM_VOLT" : 12.0,
|
||||
"SIM_SPEEDUP": 2,
|
||||
})
|
||||
|
||||
self.context_push()
|
||||
|
@ -2719,6 +2734,17 @@ class AutoTestCopter(AutoTest):
|
|||
self.start_sup_program(instance=1)
|
||||
self.context_stop_collecting('STATUSTEXT')
|
||||
self.context_pop()
|
||||
|
||||
self.set_parameters({
|
||||
# use DroneCAN ESCs for flight
|
||||
"CAN_D1_UC_ESC_BM" : 0x0f,
|
||||
# this stops us using local servo output, guaranteeing we are
|
||||
# flying on DroneCAN ESCs
|
||||
"SIM_CAN_SRV_MSK" : 0xFF,
|
||||
# we can do the flight faster
|
||||
"SIM_SPEEDUP" : 5,
|
||||
})
|
||||
|
||||
self.CopterMission()
|
||||
|
||||
def TakeoffAlt(self):
|
||||
|
|
|
@ -402,7 +402,8 @@ tester_class_map = {
|
|||
}
|
||||
|
||||
supplementary_test_binary_map = {
|
||||
"test.CAN": ["sitl_periph_gps.AP_Periph", "sitl_periph_gps.AP_Periph.1"],
|
||||
"test.CAN": ["sitl_periph_gps:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501
|
||||
"sitl_periph_gps:AP_Periph:1:Tools/autotest/default_params/periph.parm"],
|
||||
}
|
||||
|
||||
|
||||
|
@ -513,16 +514,19 @@ def run_step(step):
|
|||
if step.startswith(k):
|
||||
# this test needs to use supplementary binaries
|
||||
for supplementary_test_binary in supplementary_test_binary_map[k]:
|
||||
config_name = supplementary_test_binary.split('.')[0]
|
||||
binary_name = supplementary_test_binary.split('.')[1]
|
||||
instance_num = 0
|
||||
if len(supplementary_test_binary.split('.')) >= 3:
|
||||
instance_num = int(supplementary_test_binary.split('.')[2])
|
||||
supplementary_binaries.append([util.reltopdir(os.path.join('build',
|
||||
config_name,
|
||||
'bin',
|
||||
binary_name)),
|
||||
'-I {}'.format(instance_num)])
|
||||
a = supplementary_test_binary.split(':')
|
||||
if len(a) != 4:
|
||||
raise ValueError("Bad supplementary_test_binary %s" % supplementary_test_binary)
|
||||
config_name = a[0]
|
||||
binary_name = a[1]
|
||||
instance_num = int(a[2])
|
||||
param_file = a[3].split(",")
|
||||
bin_path = util.reltopdir(os.path.join('build', config_name, 'bin', binary_name))
|
||||
customisation = '-I {}'.format(instance_num)
|
||||
sup_binary = {"binary" : bin_path,
|
||||
"customisation" : customisation,
|
||||
"param_file" : param_file}
|
||||
supplementary_binaries.append(sup_binary)
|
||||
# we are running in conjunction with a supplementary app
|
||||
# can't have speedup
|
||||
opts.speedup = 1.0
|
||||
|
|
|
@ -8061,10 +8061,11 @@ Also, ignores heartbeats not from our target system'''
|
|||
count = 0
|
||||
for sup_binary in self.sup_binaries:
|
||||
self.progress("Starting Supplementary Program ", sup_binary)
|
||||
start_sitl_args["customisations"] = [sup_binary[1]]
|
||||
start_sitl_args["customisations"] = [sup_binary['customisation']]
|
||||
start_sitl_args["supplementary"] = True
|
||||
start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary[0]), count)
|
||||
sup_prog_link = util.start_SITL(sup_binary[0], **start_sitl_args)
|
||||
start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count)
|
||||
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
|
||||
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
|
||||
self.sup_prog.append(sup_prog_link)
|
||||
self.expect_list_add(sup_prog_link)
|
||||
count += 1
|
||||
|
@ -8107,25 +8108,18 @@ Also, ignores heartbeats not from our target system'''
|
|||
"callgrind": self.callgrind,
|
||||
"wipe": True,
|
||||
}
|
||||
if instance is None:
|
||||
for sup_binary in self.sup_binaries:
|
||||
start_sitl_args["customisations"] = [sup_binary[1]]
|
||||
if args is not None:
|
||||
start_sitl_args["customisations"] = [sup_binary[1], args]
|
||||
start_sitl_args["supplementary"] = True
|
||||
sup_prog_link = util.start_SITL(sup_binary[0], **start_sitl_args)
|
||||
time.sleep(3)
|
||||
self.sup_prog.append(sup_prog_link) # add to list
|
||||
self.expect_list_add(sup_prog_link) # add to expect list
|
||||
else:
|
||||
# start only the instance passed
|
||||
start_sitl_args["customisations"] = [self.sup_binaries[instance][1]]
|
||||
for i in range(len(self.sup_binaries)):
|
||||
if instance is not None and instance != i:
|
||||
continue
|
||||
sup_binary = self.sup_binaries[i]
|
||||
start_sitl_args["customisations"] = [sup_binary['customisation']]
|
||||
if args is not None:
|
||||
start_sitl_args["customisations"] = [self.sup_binaries[instance][1], args]
|
||||
start_sitl_args["customisations"] = [sup_binary['customisation'], args]
|
||||
start_sitl_args["supplementary"] = True
|
||||
sup_prog_link = util.start_SITL(self.sup_binaries[instance][0], **start_sitl_args)
|
||||
time.sleep(3)
|
||||
self.sup_prog[instance] = sup_prog_link # add to list
|
||||
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
|
||||
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
|
||||
time.sleep(1)
|
||||
self.sup_prog[i] = sup_prog_link # add to list
|
||||
self.expect_list_add(sup_prog_link) # add to expect list
|
||||
|
||||
def sitl_is_running(self):
|
||||
|
|
|
@ -7,3 +7,13 @@ ARSPD_TYPE 100
|
|||
RNGFND1_TYPE 100
|
||||
RNGFND1_MAX_CM 12000
|
||||
BATT_MONITOR 4
|
||||
|
||||
# by default disable motors/servos, overridden in vehicle specific parameters
|
||||
OUT1_FUNCTION -1
|
||||
OUT2_FUNCTION -1
|
||||
OUT3_FUNCTION -1
|
||||
OUT4_FUNCTION -1
|
||||
OUT5_FUNCTION -1
|
||||
OUT6_FUNCTION -1
|
||||
OUT7_FUNCTION -1
|
||||
OUT8_FUNCTION -1
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
# extra parameters for SITL peripheral quadplane
|
||||
|
||||
SIM_CAN_SRV_MSK 0x0f
|
||||
|
||||
# ESCs
|
||||
OUT1_FUNCTION 33
|
||||
OUT1_MIN 1000
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
# extra parameters for SITL peripheral quadplane
|
||||
|
||||
SIM_CAN_SRV_MSK 0xff
|
||||
|
||||
# control surfaces
|
||||
OUT1_FUNCTION 51
|
||||
OUT2_FUNCTION 52
|
||||
|
|
|
@ -536,13 +536,6 @@ def start_SITL(binary,
|
|||
cmd.extend(['--speedup', str(speedup)])
|
||||
if sim_rate_hz is not None:
|
||||
cmd.extend(['--rate', str(sim_rate_hz)])
|
||||
if defaults_filepath is not None:
|
||||
if type(defaults_filepath) == list:
|
||||
defaults = [reltopdir(path) for path in defaults_filepath]
|
||||
if len(defaults):
|
||||
cmd.extend(['--defaults', ",".join(defaults)])
|
||||
else:
|
||||
cmd.extend(['--defaults', reltopdir(defaults_filepath)])
|
||||
if unhide_parameters:
|
||||
cmd.extend(['--unhide-groups'])
|
||||
# somewhere for MAVProxy to connect to:
|
||||
|
@ -550,6 +543,14 @@ def start_SITL(binary,
|
|||
if not enable_fgview_output:
|
||||
cmd.append("--disable-fgview")
|
||||
|
||||
if defaults_filepath is not None:
|
||||
if type(defaults_filepath) == list:
|
||||
defaults = [reltopdir(path) for path in defaults_filepath]
|
||||
if len(defaults):
|
||||
cmd.extend(['--defaults', ",".join(defaults)])
|
||||
else:
|
||||
cmd.extend(['--defaults', reltopdir(defaults_filepath)])
|
||||
|
||||
cmd.extend(customisations)
|
||||
|
||||
pexpect_logfile_prefix = stdout_prefix
|
||||
|
|
Loading…
Reference in New Issue