autotest: added quadplane-can vehicle

setup with all CAN peripherals
This commit is contained in:
Andrew Tridgell 2023-08-20 07:33:08 +10:00 committed by Peter Barker
parent 4a07f7a4eb
commit 52d80241b9
8 changed files with 86 additions and 8 deletions

View File

@ -2621,7 +2621,7 @@ class AutoTestCopter(AutoTest):
"GPS_TYPE": 9,
"GPS_TYPE2": 9,
"SIM_GPS2_DISABLE": 0,
"SIM_SPEEDUP": 10,
"SIM_SPEEDUP": 5,
})
self.context_push()

View File

@ -5,4 +5,5 @@ COMPASS_ENABLE 1
BARO_ENABLE 1
ARSPD_TYPE 100
RNGFND1_TYPE 100
RNGFND1_MAX_CM 12000
BATT_MONITOR 4

View File

@ -0,0 +1,8 @@
CAN_P1_DRIVER 1
CAN_D1_UC_ESC_BM 0x0F
SIM_CAN_SRV_MSK 0xFf
SIM_VIB_MOT_MAX 270
GPS_TYPE 9
RNGFND1_TYPE 24
RNGFND1_MAX_CM 11000
BATT_MONITOR 8

View File

@ -0,0 +1,15 @@
# extra parameters for SITL peripheral quadplane
# ESCs
OUT1_FUNCTION 33
OUT1_MIN 1000
OUT1_MAX 2000
OUT2_FUNCTION 34
OUT2_MIN 1000
OUT2_MAX 2000
OUT3_FUNCTION 35
OUT3_MIN 1000
OUT3_MAX 2000
OUT4_FUNCTION 36
OUT4_MIN 1000
OUT4_MAX 2000

View File

@ -0,0 +1,13 @@
CAN_P1_DRIVER 1
CAN_D1_UC_ESC_BM 0xF0
CAN_D1_UC_ESC_OF 4
CAN_D1_UC_SRV_BM 0x0F
CAN_D1_UC_OPTION 16
SIM_CAN_SRV_MSK 0xfff
SIM_VIB_MOT_MAX 270
GPS_TYPE 9
ARSPD_TYPE 8
RNGFND1_TYPE 24
RNGFND1_MAX_CM 11000
RNGFND_LANDING 1
BATT_MONITOR 8

View File

@ -0,0 +1,21 @@
# extra parameters for SITL peripheral quadplane
# control surfaces
OUT1_FUNCTION 51
OUT2_FUNCTION 52
OUT3_FUNCTION 53
OUT4_FUNCTION 54
# ESCs
OUT5_FUNCTION 33
OUT5_MIN 1000
OUT5_MAX 2000
OUT6_FUNCTION 34
OUT6_MIN 1000
OUT6_MAX 2000
OUT7_FUNCTION 35
OUT7_MIN 1000
OUT7_MAX 2000
OUT8_FUNCTION 36
OUT8_MIN 1000
OUT8_MAX 2000

View File

@ -188,6 +188,11 @@ class VehicleInfo(object):
"default_params_filename": ["default_params/copter.parm",
"models/Callisto.param"],
},
"quad-can": {
"waf_target": "bin/arducopter",
"default_params_filename": ["default_params/copter.parm", "default_params/quad-can.parm"],
"periph_params_filename": ["default_params/periph.parm", "default_params/quad-periph.parm"],
},
},
},
"Helicopter": {
@ -260,6 +265,11 @@ class VehicleInfo(object):
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm", "default_params/plane-ice.parm", "default_params/quadplane-ice.parm"],
},
"quadplane-can": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm", "default_params/quadplane-can.parm"],
"periph_params_filename": ["default_params/periph.parm", "default_params/quadplane-periph.parm"],
},
"firefly": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/firefly.parm",

View File

@ -660,14 +660,24 @@ def start_antenna_tracker(opts):
os.chdir(oldpwd)
def start_CAN_GPS(opts):
"""Compile and run the sitl_periph_gps"""
def start_CAN_Periph(opts, frame_info):
"""Compile and run the sitl_periph"""
global can_uarta
progress("Preparing sitl_periph_gps")
options = vinfo.options["sitl_periph_gps"]['frames']['gps']
defaults_path = options.get('default_params_filename', None)
do_build(opts, options)
defaults_path = frame_info.get('periph_params_filename', None)
if defaults_path is None:
defaults_path = options.get('default_params_filename', None)
if not isinstance(defaults_path, list):
defaults_path = [defaults_path]
# add in path and make a comma separated list
defaults_path = ','.join([util.relcurdir(os.path.join(autotest_dir, p)) for p in defaults_path])
if not cmd_opts.no_rebuild:
do_build(opts, options)
exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph')
cmd = ["nice"]
cmd_name = "sitl_periph_gps"
@ -692,7 +702,7 @@ def start_CAN_GPS(opts):
cmd.append(exe)
if defaults_path is not None:
cmd.append("--defaults")
cmd.append(util.relcurdir(os.path.join(autotest_dir, defaults_path)))
cmd.append(defaults_path)
run_in_terminal_window(cmd_name, cmd)
@ -1476,8 +1486,8 @@ if cmd_opts.instance == 0:
if cmd_opts.tracker:
start_antenna_tracker(cmd_opts)
if cmd_opts.can_peripherals:
start_CAN_GPS(cmd_opts)
if cmd_opts.can_peripherals or frame_infos.get('periph_params_filename', None) is not None:
start_CAN_Periph(cmd_opts, frame_infos)
if cmd_opts.custom_location:
location = [(float)(x) for x in cmd_opts.custom_location.split(",")]