ardupilot/Tools/autotest/pysim/vehicleinfo.py

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

532 lines
22 KiB
Python
Raw Normal View History

class VehicleInfo(object):
def __init__(self):
"""
waf_target: option passed to waf's --target to create binary
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"],
},
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" ],
},
"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",
"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",
"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",
"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
},
"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",
"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
},
"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" ],
},
# SIM
"IrisRos": {
"waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter.parm",
"external": True,
},
"gazebo-iris": {
"waf_target": "bin/arducopter",
"default_params_filename": ["default_params/copter.parm",
"default_params/gazebo-iris.parm"],
"external": True,
},
2019-05-20 19:51:42 -03:00
"airsim-copter": {
"waf_target": "bin/arducopter",
"default_params_filename": ["default_params/copter.parm",
"default_params/airsim-quadX.parm"],
"external": True,
2019-05-20 19:51:42 -03:00
},
# HELICOPTER
"heli": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": "default_params/copter-heli.parm",
},
"heli-gas": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
"default_params/copter-heli-gas.parm"],
},
"heli-dual": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
"default_params/copter-heli-dual.parm"],
},
2021-09-07 00:26:24 -03:00
"heli-blade360": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
],
},
"singlecopter": {
"waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter-single.parm",
},
"coaxcopter": {
"waf_target": "bin/arducopter",
"default_params_filename": ["default_params/copter-single.parm",
"default_params/copter-coax.parm"],
},
"scrimmage-copter" : {
"waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter.parm",
"external": True,
},
"calibration": {
"extra_mavlink_cmds": "module load sitl_calibration;",
"external": True, # lies! OTOH, hard to take off with this
},
"Callisto": {
"model": "octa-quad:@ROMFS/models/Callisto.json",
"waf_target": "bin/arducopter",
"default_params_filename": [
"default_params/copter.parm",
"default_params/copter-octaquad.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"],
},
2023-11-13 11:17:25 -04:00
"freestyle": {
"model": "X:@ROMFS/models/freestyle.json",
"waf_target": "bin/arducopter",
"default_params_filename": [
"default_params/copter.parm",
"default_params/copter-X.parm",
"models/freestyle.param",
],
2023-11-13 11:17:25 -04:00
},
},
},
"Helicopter": {
"default_frame": "heli",
"frames": {
"heli": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": "default_params/copter-heli.parm",
},
"heli-gas": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
"default_params/copter-heli-gas.parm"],
},
"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-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",
},
},
},
"ArduPlane": {
"default_frame": "plane",
"frames": {
# PLANE
"quadplane-tilttri": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tilttri.parm"],
},
"quadplane-tilttrivec": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tilttrivec.parm"],
},
"quadplane-tilthvec": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/quadplane-tilthvec.parm"],
},
"quadplane-tri": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tri.parm"],
},
"quadplane-cl84" : {
"waf_target" : "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-cl84.parm"],
},
"quadplane": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/quadplane.parm",
},
"quadplane-ice": {
"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"],
},
"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",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/firefly.parm"]
2017-08-19 20:36:45 -03:00
},
"plane-elevon": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/plane-elevons.parm"],
},
"plane-vtail": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/plane-vtail.parm"],
},
"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",
"default_params_filename": ["models/plane.parm", "default_params/plane-jet.parm"],
2019-07-02 03:56:36 -03:00
},
"plane-ice": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/plane-ice.parm"],
},
"plane-3d": {
"waf_target": "bin/arduplane",
"default_params_filename": [], # defaults are loaded in SIM_Plane.cpp
},
2024-04-28 00:21:41 -03:00
"glider": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/glider.parm",
},
"quadplane-copter_tailsitter": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"],
},
"plane": {
"waf_target": "bin/arduplane",
"default_params_filename": "models/plane.parm",
},
"plane-dspoilers": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/plane-dspoilers.parm"]
},
"plane-soaring": {
"waf_target": "bin/arduplane",
"default_params_filename": ["models/plane.parm", "default_params/plane-soaring.parm"]
},
"gazebo-zephyr": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/gazebo-zephyr.parm",
"external": True,
},
"last_letter": {
"waf_target": "bin/arduplane",
"default_params_filename": "models/plane.parm",
"external": True,
},
"CRRCSim": {
"waf_target": "bin/arduplane",
"default_params_filename": "models/plane.parm",
"external": True,
},
"jsbsim": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/plane-jsbsim.parm",
"external": True,
},
"scrimmage-plane" : {
"waf_target": "bin/arduplane",
"default_params_filename": "models/plane.parm",
"external": True,
},
"calibration": {
"extra_mavlink_cmds": "module load sitl_calibration;",
"external": True, # lies! OTOH, hard to take off with this
},
2024-04-26 05:48:29 -03:00
"stratoblimp": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/stratoblimp.parm",
},
},
},
2020-03-26 20:14:17 -03:00
"Rover": {
"default_frame": "rover",
"frames": {
# ROVER
"rover": {
"waf_target": "bin/ardurover",
"default_params_filename": "default_params/rover.parm",
},
"rover-skid": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/rover-skid.parm"],
},
"rover-omni3mecanum": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/rover-omni3mecanum.parm"],
},
"rover-vectored": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/rover-vectored.parm"],
},
"balancebot": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/rover-skid.parm",
"default_params/balancebot.parm"],
},
"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"],
},
"sailboat": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/sailboat.parm"],
},
"sailboat-motor": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/sailboat-motor.parm"],
},
"gazebo-rover": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/rover-skid.parm"],
},
"airsim-rover": {
"waf_target": "bin/ardurover",
"default_params_filename": ["default_params/rover.parm",
"default_params/airsim-rover.parm"],
},
"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",
},
"gazebo-bluerov2": {
"waf_target": "bin/ardusub",
"default_params_filename": "default_params/sub.parm",
},
},
},
"AntennaTracker": {
"default_frame": "tracker",
"frames": {
"tracker": {
"waf_target": "bin/antennatracker",
},
},
},
"sitl_periph_universal": {
"frames": {
"universal": {
"configure_target": "sitl_periph_universal",
"waf_target": "bin/AP_Periph",
"default_params_filename": "default_params/periph.parm",
},
}
},
}
def default_frame(self, vehicle):
return self.options[vehicle]["default_frame"]
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"""
default_frame = self.default_frame(vehicle)
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"]:
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:
print("WARNING: no config for frame (%s)" % frame)
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:
ret["waf_target"] = self.default_waf_target(vehicle)
if opts.build_target is not None:
ret["waf_target"] = opts.build_target
return ret