2017-05-24 04:18:24 -03:00
|
|
|
class VehicleInfo(object):
|
|
|
|
|
|
|
|
def __init__(self):
|
|
|
|
"""
|
2021-01-15 02:07:04 -04:00
|
|
|
waf_target: option passed to waf's --target to create binary
|
2017-05-24 04:18:24 -03:00
|
|
|
default_params_filename: filename of default parameters file. Taken to be relative to autotest dir.
|
|
|
|
extra_mavlink_cmds: extra parameters that will be passed to mavproxy
|
|
|
|
"""
|
|
|
|
self.options = {
|
|
|
|
"ArduCopter": {
|
|
|
|
"default_frame": "quad",
|
|
|
|
"frames": {
|
|
|
|
# COPTER
|
|
|
|
"+": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": "default_params/copter.parm",
|
|
|
|
},
|
|
|
|
"quad": {
|
|
|
|
"model": "+",
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": "default_params/copter.parm",
|
|
|
|
},
|
|
|
|
"X": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2024-02-16 22:51:45 -04:00
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-X.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2019-01-31 23:31:17 -04:00
|
|
|
"bfx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-bfx.parm" ],
|
|
|
|
},
|
|
|
|
"djix": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-djix.parm" ],
|
|
|
|
},
|
|
|
|
"cwx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-cwx.parm" ],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"hexa": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-hexa.parm" ],
|
|
|
|
},
|
2024-04-11 04:46:25 -03:00
|
|
|
"hexax": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-hexa.parm",
|
|
|
|
"default_params/copter-X.parm", ],
|
|
|
|
},
|
2020-02-01 05:16:56 -04:00
|
|
|
"hexa-cwx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-05-01 05:11:05 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-hexa.parm",
|
|
|
|
"default_params/copter-hexa-cwx.parm"
|
|
|
|
],
|
2020-02-01 05:16:56 -04:00
|
|
|
},
|
2020-01-28 08:04:26 -04:00
|
|
|
"hexa-dji": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-05-01 05:11:05 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-hexa.parm",
|
|
|
|
"default_params/copter-hexa-dji.parm"
|
|
|
|
],
|
2020-02-01 05:16:56 -04:00
|
|
|
},
|
|
|
|
"octa-cwx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-04-28 04:48:01 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-octa.parm",
|
|
|
|
"default_params/copter-octa-cwx.parm"
|
|
|
|
],
|
2020-02-01 05:16:56 -04:00
|
|
|
},
|
|
|
|
"octa-quad-cwx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-05-01 05:11:05 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-octaquad.parm",
|
|
|
|
"default_params/copter-octaquad-cwx.parm"
|
|
|
|
],
|
2020-01-28 08:04:26 -04:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"octa-quad": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-octaquad.parm" ],
|
|
|
|
},
|
|
|
|
"octa": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-octa.parm" ],
|
|
|
|
},
|
2020-01-28 08:04:26 -04:00
|
|
|
"octa-dji": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-04-28 04:43:28 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-octa.parm",
|
|
|
|
"default_params/copter-octa-dji.parm"
|
|
|
|
],
|
2020-01-28 08:04:26 -04:00
|
|
|
},
|
2020-09-16 12:01:02 -03:00
|
|
|
"deca": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-deca.parm" ],
|
|
|
|
},
|
|
|
|
"deca-cwx": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2021-10-21 14:35:47 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-deca.parm",
|
|
|
|
"default_params/copter-deca-cwx.parm"
|
|
|
|
],
|
2020-09-16 12:01:02 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"tri": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-tri.parm" ],
|
|
|
|
},
|
|
|
|
"y6": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-y6.parm" ],
|
|
|
|
},
|
2017-05-27 01:52:30 -03:00
|
|
|
"dodeca-hexa": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/copter-dodecahexa.parm" ],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
# SIM
|
|
|
|
"IrisRos": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": "default_params/copter.parm",
|
2021-03-02 22:52:04 -04:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"gazebo-iris": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/gazebo-iris.parm"],
|
2021-03-02 22:52:04 -04:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2019-05-20 19:51:42 -03:00
|
|
|
"airsim-copter": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2019-12-16 18:21:07 -04:00
|
|
|
"default_params_filename": ["default_params/copter.parm",
|
|
|
|
"default_params/airsim-quadX.parm"],
|
2021-03-02 22:52:04 -04:00
|
|
|
"external": True,
|
2019-05-20 19:51:42 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
# HELICOPTER
|
|
|
|
"heli": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": "default_params/copter-heli.parm",
|
|
|
|
},
|
2023-05-30 00:38:27 -03:00
|
|
|
"heli-gas": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
"default_params/copter-heli-gas.parm"],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"heli-dual": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
2017-05-26 22:03:57 -03:00
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
"default_params/copter-heli-dual.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2021-09-07 00:26:24 -03:00
|
|
|
"heli-blade360": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"singlecopter": {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": "default_params/copter-single.parm",
|
|
|
|
},
|
|
|
|
"coaxcopter": {
|
|
|
|
"waf_target": "bin/arducopter",
|
2017-05-28 07:39:29 -03:00
|
|
|
"default_params_filename": ["default_params/copter-single.parm",
|
|
|
|
"default_params/copter-coax.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2019-07-18 14:38:11 -03:00
|
|
|
"scrimmage-copter" : {
|
|
|
|
"waf_target": "bin/arducopter",
|
|
|
|
"default_params_filename": "default_params/copter.parm",
|
2021-03-02 22:52:04 -04:00
|
|
|
"external": True,
|
2019-07-18 14:38:11 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"calibration": {
|
|
|
|
"extra_mavlink_cmds": "module load sitl_calibration;",
|
2021-03-02 22:52:04 -04:00
|
|
|
"external": True, # lies! OTOH, hard to take off with this
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2020-10-24 22:45:01 -03:00
|
|
|
"Callisto": {
|
|
|
|
"model": "octa-quad:@ROMFS/models/Callisto.json",
|
|
|
|
"waf_target": "bin/arducopter",
|
2024-04-18 00:08:28 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-octaquad.parm",
|
|
|
|
"models/Callisto.param",
|
|
|
|
],
|
2020-10-24 22:45:01 -03:00
|
|
|
},
|
2023-08-19 18:33:08 -03:00
|
|
|
"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"],
|
|
|
|
},
|
2023-11-13 11:17:25 -04:00
|
|
|
"freestyle": {
|
|
|
|
"model": "X:@ROMFS/models/freestyle.json",
|
|
|
|
"waf_target": "bin/arducopter",
|
2024-04-18 00:08:28 -03:00
|
|
|
"default_params_filename": [
|
|
|
|
"default_params/copter.parm",
|
|
|
|
"default_params/copter-X.parm",
|
|
|
|
"models/freestyle.param",
|
|
|
|
],
|
2023-11-13 11:17:25 -04:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
},
|
2021-06-08 06:49:31 -03:00
|
|
|
"Helicopter": {
|
|
|
|
"default_frame": "heli",
|
|
|
|
"frames": {
|
|
|
|
"heli": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": "default_params/copter-heli.parm",
|
|
|
|
},
|
2023-05-30 00:38:27 -03:00
|
|
|
"heli-gas": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
"default_params/copter-heli-gas.parm"],
|
|
|
|
},
|
2021-06-08 06:49:31 -03:00
|
|
|
"heli-dual": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
"default_params/copter-heli-dual.parm"],
|
|
|
|
},
|
|
|
|
# "heli-compound": {
|
|
|
|
# "waf_target": "bin/arducopter-heli",
|
|
|
|
# "default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
# "default_params/copter-heli-compound.parm"],
|
|
|
|
# },
|
2021-09-07 00:26:24 -03:00
|
|
|
"heli-blade360": {
|
|
|
|
"waf_target": "bin/arducopter-heli",
|
|
|
|
"default_params_filename": ["default_params/copter-heli.parm",
|
|
|
|
],
|
|
|
|
},
|
2021-06-08 06:49:31 -03:00
|
|
|
},
|
|
|
|
},
|
2021-03-18 00:12:54 -03:00
|
|
|
"Blimp": {
|
2021-08-06 01:09:28 -03:00
|
|
|
"default_frame": "Blimp",
|
2021-03-18 00:12:54 -03:00
|
|
|
"frames": {
|
2021-08-06 01:09:28 -03:00
|
|
|
"Blimp": {
|
2021-03-18 00:12:54 -03:00
|
|
|
"waf_target": "bin/blimp",
|
|
|
|
"default_params_filename": "default_params/blimp.parm",
|
|
|
|
},
|
|
|
|
},
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"ArduPlane": {
|
2017-11-06 00:44:26 -04:00
|
|
|
"default_frame": "plane",
|
2017-05-24 04:18:24 -03:00
|
|
|
"frames": {
|
|
|
|
# PLANE
|
|
|
|
"quadplane-tilttri": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2024-02-17 04:28:05 -04:00
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/quadplane-tilttri.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"quadplane-tilttrivec": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2024-02-17 04:28:05 -04:00
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/quadplane-tilttrivec.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2017-08-20 16:12:06 -03:00
|
|
|
"quadplane-tilthvec": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/quadplane-tilthvec.parm"],
|
2017-08-20 16:12:06 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"quadplane-tri": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2024-02-17 04:28:05 -04:00
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/quadplane-tri.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"quadplane-cl84" : {
|
|
|
|
"waf_target" : "bin/arduplane",
|
2024-02-17 04:28:05 -04:00
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/quadplane-cl84.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"quadplane": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/quadplane.parm",
|
|
|
|
},
|
2022-09-26 23:01:30 -03:00
|
|
|
"quadplane-ice": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": ["default_params/quadplane.parm", "default_params/plane-ice.parm", "default_params/quadplane-ice.parm"],
|
|
|
|
},
|
2023-08-19 18:33:08 -03:00
|
|
|
"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"],
|
|
|
|
},
|
2024-02-17 04:28:05 -04:00
|
|
|
"quadplane-tilt": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/quadplane-tilt.parm"],
|
|
|
|
},
|
2017-08-19 20:36:45 -03:00
|
|
|
"firefly": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2024-02-17 04:28:05 -04:00
|
|
|
"default_params_filename": ["default_params/quadplane.parm",
|
|
|
|
"default_params/firefly.parm"]
|
2017-08-19 20:36:45 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"plane-elevon": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-elevons.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"plane-vtail": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-vtail.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"plane-tailsitter": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/plane-tailsitter.parm",
|
|
|
|
},
|
2019-07-02 03:56:36 -03:00
|
|
|
"plane-jet": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-jet.parm"],
|
2019-07-02 03:56:36 -03:00
|
|
|
},
|
2022-09-26 23:01:30 -03:00
|
|
|
"plane-ice": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-ice.parm"],
|
2022-09-26 23:01:30 -03:00
|
|
|
},
|
2022-10-15 05:35:50 -03:00
|
|
|
"plane-3d": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": [], # defaults are loaded in SIM_Plane.cpp
|
2022-10-15 05:35:50 -03:00
|
|
|
},
|
2024-04-28 00:21:41 -03:00
|
|
|
"glider": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/glider.parm",
|
|
|
|
},
|
2019-04-05 15:28:41 -03:00
|
|
|
"quadplane-copter_tailsitter": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"plane": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": "models/plane.parm",
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2017-07-01 03:03:04 -03:00
|
|
|
"plane-dspoilers": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-dspoilers.parm"]
|
2017-07-01 03:03:04 -03:00
|
|
|
},
|
2019-05-26 06:56:10 -03:00
|
|
|
"plane-soaring": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": ["models/plane.parm", "default_params/plane-soaring.parm"]
|
2019-05-26 06:56:10 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"gazebo-zephyr": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/gazebo-zephyr.parm",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"last_letter": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": "models/plane.parm",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"CRRCSim": {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": "models/plane.parm",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
"jsbsim": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/plane-jsbsim.parm",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True,
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2019-07-18 14:38:11 -03:00
|
|
|
"scrimmage-plane" : {
|
|
|
|
"waf_target": "bin/arduplane",
|
2022-11-08 17:01:54 -04:00
|
|
|
"default_params_filename": "models/plane.parm",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True,
|
2019-07-18 14:38:11 -03:00
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"calibration": {
|
|
|
|
"extra_mavlink_cmds": "module load sitl_calibration;",
|
2021-06-20 22:33:12 -03:00
|
|
|
"external": True, # lies! OTOH, hard to take off with this
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2024-04-26 05:48:29 -03:00
|
|
|
"stratoblimp": {
|
|
|
|
"waf_target": "bin/arduplane",
|
|
|
|
"default_params_filename": "default_params/stratoblimp.parm",
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
},
|
2020-03-26 20:14:17 -03:00
|
|
|
"Rover": {
|
2017-05-24 04:18:24 -03:00
|
|
|
"default_frame": "rover",
|
|
|
|
"frames": {
|
|
|
|
# ROVER
|
|
|
|
"rover": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": "default_params/rover.parm",
|
|
|
|
},
|
|
|
|
"rover-skid": {
|
|
|
|
"waf_target": "bin/ardurover",
|
2017-05-26 22:13:40 -03:00
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/rover-skid.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2024-07-16 09:38:01 -03:00
|
|
|
"rover-omni3mecanum": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/rover-omni3mecanum.parm"],
|
|
|
|
},
|
2021-03-30 09:13:37 -03:00
|
|
|
"rover-vectored": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/rover-vectored.parm"],
|
|
|
|
},
|
2018-05-18 06:59:32 -03:00
|
|
|
"balancebot": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/rover-skid.parm",
|
|
|
|
"default_params/balancebot.parm"],
|
|
|
|
},
|
2021-11-18 21:54:41 -04:00
|
|
|
"motorboat": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/motorboat.parm"],
|
|
|
|
},
|
2024-07-16 07:53:34 -03:00
|
|
|
"motorboat-skid": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/motorboat.parm",
|
|
|
|
"default_params/rover-skid.parm"],
|
|
|
|
},
|
2018-09-24 04:16:54 -03:00
|
|
|
"sailboat": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/sailboat.parm"],
|
|
|
|
},
|
2019-08-13 18:24:00 -03:00
|
|
|
"sailboat-motor": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/sailboat-motor.parm"],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"gazebo-rover": {
|
|
|
|
"waf_target": "bin/ardurover",
|
2017-05-26 22:13:40 -03:00
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/rover-skid.parm"],
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
2019-07-31 04:13:02 -03:00
|
|
|
"airsim-rover": {
|
|
|
|
"waf_target": "bin/ardurover",
|
|
|
|
"default_params_filename": ["default_params/rover.parm",
|
|
|
|
"default_params/airsim-rover.parm"],
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
"calibration": {
|
|
|
|
"extra_mavlink_cmds": "module load sitl_calibration;",
|
|
|
|
},
|
|
|
|
},
|
|
|
|
},
|
|
|
|
"ArduSub": {
|
|
|
|
"default_frame": "vectored",
|
|
|
|
"frames": {
|
|
|
|
"vectored": {
|
|
|
|
"waf_target": "bin/ardusub",
|
|
|
|
"default_params_filename": "default_params/sub.parm",
|
|
|
|
},
|
2019-08-05 13:44:46 -03:00
|
|
|
"vectored_6dof": {
|
|
|
|
"waf_target": "bin/ardusub",
|
|
|
|
"default_params_filename": "default_params/sub-6dof.parm",
|
|
|
|
},
|
2017-12-04 10:38:20 -04:00
|
|
|
"gazebo-bluerov2": {
|
|
|
|
"waf_target": "bin/ardusub",
|
|
|
|
"default_params_filename": "default_params/sub.parm",
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
},
|
|
|
|
},
|
|
|
|
"AntennaTracker": {
|
|
|
|
"default_frame": "tracker",
|
|
|
|
"frames": {
|
|
|
|
"tracker": {
|
|
|
|
"waf_target": "bin/antennatracker",
|
|
|
|
},
|
|
|
|
},
|
|
|
|
},
|
2024-01-11 22:50:43 -04:00
|
|
|
"sitl_periph_universal": {
|
2022-08-21 18:20:39 -03:00
|
|
|
"frames": {
|
2024-01-11 22:50:43 -04:00
|
|
|
"universal": {
|
|
|
|
"configure_target": "sitl_periph_universal",
|
2022-08-21 18:20:39 -03:00
|
|
|
"waf_target": "bin/AP_Periph",
|
2023-08-17 18:54:19 -03:00
|
|
|
"default_params_filename": "default_params/periph.parm",
|
2022-08-21 18:20:39 -03:00
|
|
|
},
|
|
|
|
}
|
|
|
|
},
|
2017-05-24 04:18:24 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-05-24 04:55:03 -03:00
|
|
|
def default_frame(self, vehicle):
|
|
|
|
return self.options[vehicle]["default_frame"]
|
|
|
|
|
2017-05-24 04:18:24 -03:00
|
|
|
def default_waf_target(self, vehicle):
|
|
|
|
"""Returns a waf target based on vehicle type, which is often determined by which directory the user is in"""
|
2017-05-24 04:55:03 -03:00
|
|
|
default_frame = self.default_frame(vehicle)
|
2017-05-24 04:18:24 -03:00
|
|
|
return self.options[vehicle]["frames"][default_frame]["waf_target"]
|
|
|
|
|
|
|
|
def options_for_frame(self, frame, vehicle, opts):
|
|
|
|
"""Return informatiom about how to sitl for frame e.g. build-type==sitl"""
|
|
|
|
ret = None
|
|
|
|
frames = self.options[vehicle]["frames"]
|
|
|
|
if frame in frames:
|
|
|
|
ret = self.options[vehicle]["frames"][frame]
|
|
|
|
else:
|
2019-05-20 19:51:42 -03:00
|
|
|
for p in ["octa", "tri", "y6", "firefly", "heli", "gazebo", "last_letter", "jsbsim", "quadplane", "plane-elevon", "plane-vtail", "plane", "airsim"]:
|
2017-05-24 04:18:24 -03:00
|
|
|
if frame.startswith(p):
|
|
|
|
ret = self.options[vehicle]["frames"][p]
|
|
|
|
break
|
|
|
|
if ret is None:
|
|
|
|
if frame.endswith("-heli"):
|
|
|
|
ret = self.options[vehicle]["frames"]["heli"]
|
|
|
|
if ret is None:
|
2017-06-02 03:53:55 -03:00
|
|
|
print("WARNING: no config for frame (%s)" % frame)
|
2017-05-24 04:18:24 -03:00
|
|
|
ret = {}
|
|
|
|
|
|
|
|
if "model" not in ret:
|
|
|
|
ret["model"] = frame
|
|
|
|
|
|
|
|
if "sitl-port" not in ret:
|
|
|
|
ret["sitl-port"] = True
|
|
|
|
|
|
|
|
if opts.model is not None:
|
|
|
|
ret["model"] = opts.model
|
|
|
|
|
|
|
|
if (ret["model"].find("xplane") != -1 or ret["model"].find("flightaxis") != -1):
|
|
|
|
ret["sitl-port"] = False
|
|
|
|
|
|
|
|
|
|
|
|
if "waf_target" not in ret:
|
2017-06-02 03:53:55 -03:00
|
|
|
ret["waf_target"] = self.default_waf_target(vehicle)
|
2017-05-24 04:18:24 -03:00
|
|
|
|
|
|
|
if opts.build_target is not None:
|
|
|
|
ret["waf_target"] = opts.build_target
|
|
|
|
|
|
|
|
return ret
|
|
|
|
|
|
|
|
|
|
|
|
|