Path: blob/master/Tools/autotest/pysim/vehicleinfo.py
9873 views
# flake8: noqa12class VehicleInfo(object):34def __init__(self):5"""6waf_target: option passed to waf's --target to create binary7default_params_filename: filename of default parameters file. Taken to be relative to autotest dir.8extra_mavlink_cmds: extra parameters that will be passed to mavproxy9"""10self.options = {11"ArduCopter": {12"default_frame": "quad",13"frames": {14# COPTER15"+": {16"waf_target": "bin/arducopter",17"default_params_filename": "default_params/copter.parm",18},19"quad": {20"model": "+",21"waf_target": "bin/arducopter",22"default_params_filename": "default_params/copter.parm",23},24"X": {25"waf_target": "bin/arducopter",26"default_params_filename": ["default_params/copter.parm",27"default_params/copter-X.parm"],28},29"bfx": {30"waf_target": "bin/arducopter",31"default_params_filename": ["default_params/copter.parm",32"default_params/copter-bfx.parm" ],33},34"djix": {35"waf_target": "bin/arducopter",36"default_params_filename": ["default_params/copter.parm",37"default_params/copter-djix.parm" ],38},39"cwx": {40"waf_target": "bin/arducopter",41"default_params_filename": ["default_params/copter.parm",42"default_params/copter-cwx.parm" ],43},44"hexa": {45"waf_target": "bin/arducopter",46"default_params_filename": ["default_params/copter.parm",47"default_params/copter-hexa.parm" ],48},49"hexax": {50"waf_target": "bin/arducopter",51"default_params_filename": ["default_params/copter.parm",52"default_params/copter-hexa.parm",53"default_params/copter-X.parm", ],54},55"hexa-cwx": {56"waf_target": "bin/arducopter",57"default_params_filename": [58"default_params/copter.parm",59"default_params/copter-hexa.parm",60"default_params/copter-hexa-cwx.parm"61],62},63"hexa-dji": {64"waf_target": "bin/arducopter",65"default_params_filename": [66"default_params/copter.parm",67"default_params/copter-hexa.parm",68"default_params/copter-hexa-dji.parm"69],70},71"octa-cwx": {72"waf_target": "bin/arducopter",73"default_params_filename": [74"default_params/copter.parm",75"default_params/copter-octa.parm",76"default_params/copter-octa-cwx.parm"77],78},79"octa-quad-cwx": {80"waf_target": "bin/arducopter",81"default_params_filename": [82"default_params/copter.parm",83"default_params/copter-octaquad.parm",84"default_params/copter-octaquad-cwx.parm"85],86},87"octa-quad": {88"waf_target": "bin/arducopter",89"default_params_filename": ["default_params/copter.parm",90"default_params/copter-octaquad.parm" ],91},92"octa-quad-cor": {93"waf_target": "bin/arducopter",94"default_params_filename": ["default_params/copter.parm",95"default_params/copter-octaquad-cor.parm" ],96},97"octa-quad-cw-cor": {98"waf_target": "bin/arducopter",99"default_params_filename": ["default_params/copter.parm",100"default_params/copter-octaquad-cw-cor.parm" ],101},102"octa": {103"waf_target": "bin/arducopter",104"default_params_filename": ["default_params/copter.parm",105"default_params/copter-octa.parm" ],106},107"octa-dji": {108"waf_target": "bin/arducopter",109"default_params_filename": [110"default_params/copter.parm",111"default_params/copter-octa.parm",112"default_params/copter-octa-dji.parm"113],114},115"deca": {116"waf_target": "bin/arducopter",117"default_params_filename": ["default_params/copter.parm",118"default_params/copter-deca.parm" ],119},120"deca-cwx": {121"waf_target": "bin/arducopter",122"default_params_filename": [123"default_params/copter.parm",124"default_params/copter-deca.parm",125"default_params/copter-deca-cwx.parm"126],127},128"tri": {129"waf_target": "bin/arducopter",130"default_params_filename": ["default_params/copter.parm",131"default_params/copter-tri.parm" ],132},133"y6": {134"waf_target": "bin/arducopter",135"default_params_filename": ["default_params/copter.parm",136"default_params/copter-y6.parm" ],137},138"dodeca-hexa": {139"waf_target": "bin/arducopter",140"default_params_filename": ["default_params/copter.parm",141"default_params/copter-dodecahexa.parm" ],142},143"dotriaconta_octaquad_x": {144"waf_target": "bin/arducopter",145"default_params_filename": [146"default_params/copter.parm",147"default_params/copter-dotriaconta_octaquad_x.parm",148],149"frame_example_script": "MotorMatrix_dotriaconta_octaquad_x.lua",150},151"hexadeca-octa": {152"waf_target": "bin/arducopter",153"default_params_filename": [154"default_params/copter.parm",155"default_params/copter-hexadeca_octa.parm"156],157"frame_example_script": "MotorMatrix_hexadeca_octa.lua",158},159"hexadeca-octa-cwx": {160"waf_target": "bin/arducopter",161"default_params_filename": [162"default_params/copter.parm",163"default_params/copter-hexadeca_octa.parm",164"default_params/copter-hexadeca_octa_cwx.parm"165],166"frame_example_script": "MotorMatrix_hexadeca_octa_cw_x.lua",167},168# SIM169"IrisRos": {170"waf_target": "bin/arducopter",171"default_params_filename": "default_params/copter.parm",172"external": True,173},174"gazebo-iris": {175"waf_target": "bin/arducopter",176"default_params_filename": ["default_params/copter.parm",177"default_params/gazebo-iris.parm"],178"external": True,179},180"airsim-copter": {181"waf_target": "bin/arducopter",182"default_params_filename": ["default_params/copter.parm",183"default_params/airsim-quadX.parm"],184"external": True,185},186# HELICOPTER187"heli": {188"waf_target": "bin/arducopter-heli",189"default_params_filename": "default_params/copter-heli.parm",190},191"heli-gas": {192"waf_target": "bin/arducopter-heli",193"default_params_filename": ["default_params/copter-heli.parm",194"default_params/copter-heli-gas.parm"],195},196"heli-dual": {197"waf_target": "bin/arducopter-heli",198"default_params_filename": ["default_params/copter-heli.parm",199"default_params/copter-heli-dual.parm"],200},201"heli-blade360": {202"waf_target": "bin/arducopter-heli",203"default_params_filename": ["default_params/copter-heli.parm",204],205},206"singlecopter": {207"waf_target": "bin/arducopter",208"default_params_filename": "default_params/copter-single.parm",209},210"coaxcopter": {211"waf_target": "bin/arducopter",212"default_params_filename": ["default_params/copter-single.parm",213"default_params/copter-coax.parm"],214},215"scrimmage-copter" : {216"waf_target": "bin/arducopter",217"default_params_filename": "default_params/copter.parm",218"external": True,219},220"calibration": {221"extra_mavlink_cmds": "module load sitl_calibration;",222"external": True, # lies! OTOH, hard to take off with this223},224"Callisto": {225"model": "octa-quad:@ROMFS/models/Callisto.json",226"waf_target": "bin/arducopter",227"default_params_filename": [228"default_params/copter.parm",229"default_params/copter-octaquad.parm",230"models/Callisto.param",231],232},233"quad-can": {234"waf_target": "bin/arducopter",235"default_params_filename": ["default_params/copter.parm", "default_params/quad-can.parm"],236"periph_params_filename": ["default_params/periph.parm", "default_params/quad-periph.parm"],237},238"freestyle": {239"model": "X:@ROMFS/models/freestyle.json",240"waf_target": "bin/arducopter",241"default_params_filename": [242"default_params/copter.parm",243"default_params/copter-X.parm",244"models/freestyle.param",245],246},247},248},249"Helicopter": {250"default_frame": "heli",251"frames": {252"heli": {253"waf_target": "bin/arducopter-heli",254"default_params_filename": "default_params/copter-heli.parm",255},256"heli-gas": {257"waf_target": "bin/arducopter-heli",258"default_params_filename": ["default_params/copter-heli.parm",259"default_params/copter-heli-gas.parm"],260},261"heli-dual": {262"waf_target": "bin/arducopter-heli",263"default_params_filename": ["default_params/copter-heli.parm",264"default_params/copter-heli-dual.parm"],265},266# "heli-compound": {267# "waf_target": "bin/arducopter-heli",268# "default_params_filename": ["default_params/copter-heli.parm",269# "default_params/copter-heli-compound.parm"],270# },271"heli-blade360": {272"waf_target": "bin/arducopter-heli",273"default_params_filename": ["default_params/copter-heli.parm",274],275},276},277},278"Blimp": {279"default_frame": "Blimp",280"frames": {281"Blimp": {282"waf_target": "bin/blimp",283"default_params_filename": "default_params/blimp.parm",284},285},286},287"ArduPlane": {288"default_frame": "plane",289"frames": {290# PLANE291"quadplane-tilttri": {292"waf_target": "bin/arduplane",293"default_params_filename": ["default_params/quadplane.parm",294"default_params/quadplane-tilttri.parm"],295},296"quadplane-tilttrivec": {297"waf_target": "bin/arduplane",298"default_params_filename": ["default_params/quadplane.parm",299"default_params/quadplane-tilttrivec.parm"],300},301"quadplane-tilthvec": {302"waf_target": "bin/arduplane",303"default_params_filename": ["models/plane.parm", "default_params/quadplane-tilthvec.parm"],304},305"quadplane-tri": {306"waf_target": "bin/arduplane",307"default_params_filename": ["default_params/quadplane.parm",308"default_params/quadplane-tri.parm"],309},310"quadplane-cl84" : {311"waf_target" : "bin/arduplane",312"default_params_filename": ["default_params/quadplane.parm",313"default_params/quadplane-cl84.parm"],314},315"quadplane": {316"waf_target": "bin/arduplane",317"default_params_filename": "default_params/quadplane.parm",318},319"quadplane-ice": {320"waf_target": "bin/arduplane",321"default_params_filename": ["default_params/quadplane.parm", "default_params/plane-ice.parm", "default_params/quadplane-ice.parm"],322},323"quadplane-can": {324"waf_target": "bin/arduplane",325"default_params_filename": ["default_params/quadplane.parm", "default_params/quadplane-can.parm"],326"periph_params_filename": ["default_params/periph.parm", "default_params/quadplane-periph.parm"],327},328"quadplane-tilt": {329"waf_target": "bin/arduplane",330"default_params_filename": ["default_params/quadplane.parm",331"default_params/quadplane-tilt.parm"],332},333"firefly": {334"waf_target": "bin/arduplane",335"default_params_filename": ["default_params/quadplane.parm",336"default_params/firefly.parm"]337},338"plane-elevon": {339"waf_target": "bin/arduplane",340"default_params_filename": ["models/plane.parm", "default_params/plane-elevons.parm"],341},342"plane-vtail": {343"waf_target": "bin/arduplane",344"default_params_filename": ["models/plane.parm", "default_params/plane-vtail.parm"],345},346"plane-tailsitter": {347"waf_target": "bin/arduplane",348"default_params_filename": "default_params/plane-tailsitter.parm",349},350"plane-jet": {351"waf_target": "bin/arduplane",352"default_params_filename": ["models/plane.parm", "default_params/plane-jet.parm"],353},354"plane-ice": {355"waf_target": "bin/arduplane",356"default_params_filename": ["models/plane.parm", "default_params/plane-ice.parm"],357},358"plane-3d": {359"waf_target": "bin/arduplane",360"default_params_filename": [], # defaults are loaded in SIM_Plane.cpp361},362"glider": {363"waf_target": "bin/arduplane",364"default_params_filename": "default_params/glider.parm",365},366"quadplane-copter_tailsitter": {367"waf_target": "bin/arduplane",368"default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"],369},370"plane": {371"waf_target": "bin/arduplane",372"default_params_filename": "models/plane.parm",373},374"plane-dspoilers": {375"waf_target": "bin/arduplane",376"default_params_filename": ["models/plane.parm", "default_params/plane-dspoilers.parm"]377},378"plane-redundant": {379"waf_target": "bin/arduplane",380"default_params_filename": ["models/plane.parm", "default_params/plane-redundant.parm"]381},382"plane-soaring": {383"waf_target": "bin/arduplane",384"default_params_filename": ["models/plane.parm", "default_params/plane-soaring.parm"]385},386"gazebo-zephyr": {387"waf_target": "bin/arduplane",388"default_params_filename": "default_params/gazebo-zephyr.parm",389"external": True,390},391"last_letter": {392"waf_target": "bin/arduplane",393"default_params_filename": "models/plane.parm",394"external": True,395},396"CRRCSim": {397"waf_target": "bin/arduplane",398"default_params_filename": "models/plane.parm",399"external": True,400},401"jsbsim": {402"waf_target": "bin/arduplane",403"default_params_filename": "default_params/plane-jsbsim.parm",404"external": True,405},406"scrimmage-plane" : {407"waf_target": "bin/arduplane",408"default_params_filename": "models/plane.parm",409"external": True,410},411"calibration": {412"extra_mavlink_cmds": "module load sitl_calibration;",413"external": True, # lies! OTOH, hard to take off with this414},415"stratoblimp": {416"waf_target": "bin/arduplane",417"default_params_filename": "default_params/stratoblimp.parm",418},419},420},421"Rover": {422"default_frame": "rover",423"frames": {424# ROVER425"rover": {426"waf_target": "bin/ardurover",427"default_params_filename": "default_params/rover.parm",428},429"rover-skid": {430"waf_target": "bin/ardurover",431"default_params_filename": ["default_params/rover.parm",432"default_params/rover-skid.parm"],433},434"rover-omni3mecanum": {435"waf_target": "bin/ardurover",436"default_params_filename": ["default_params/rover.parm",437"default_params/rover-omni3mecanum.parm"],438},439"rover-vectored": {440"waf_target": "bin/ardurover",441"default_params_filename": ["default_params/rover.parm",442"default_params/rover-vectored.parm"],443},444"balancebot": {445"waf_target": "bin/ardurover",446"default_params_filename": ["default_params/rover.parm",447"default_params/rover-skid.parm",448"default_params/balancebot.parm"],449},450"motorboat": {451"waf_target": "bin/ardurover",452"default_params_filename": ["default_params/rover.parm",453"default_params/motorboat.parm"],454},455"motorboat-skid": {456"waf_target": "bin/ardurover",457"default_params_filename": ["default_params/rover.parm",458"default_params/motorboat.parm",459"default_params/rover-skid.parm"],460},461"sailboat": {462"waf_target": "bin/ardurover",463"default_params_filename": ["default_params/rover.parm",464"default_params/sailboat.parm"],465},466"sailboat-motor": {467"waf_target": "bin/ardurover",468"default_params_filename": ["default_params/rover.parm",469"default_params/sailboat-motor.parm"],470},471"gazebo-rover": {472"waf_target": "bin/ardurover",473"default_params_filename": ["default_params/rover.parm",474"default_params/rover-skid.parm"],475"external": True,476},477"airsim-rover": {478"waf_target": "bin/ardurover",479"default_params_filename": ["default_params/rover.parm",480"default_params/airsim-rover.parm"],481"external": True,482},483"calibration": {484"extra_mavlink_cmds": "module load sitl_calibration;",485"external": True,486},487},488},489"ArduSub": {490"default_frame": "vectored",491"frames": {492"vectored": {493"waf_target": "bin/ardusub",494"default_params_filename": "default_params/sub.parm",495},496"vectored_6dof": {497"waf_target": "bin/ardusub",498"default_params_filename": "default_params/sub-6dof.parm",499},500"gazebo-bluerov2": {501"waf_target": "bin/ardusub",502"default_params_filename": "default_params/sub.parm",503},504},505},506"AntennaTracker": {507"default_frame": "tracker",508"frames": {509"tracker": {510"waf_target": "bin/antennatracker",511},512},513},514"sitl_periph_universal": {515"frames": {516"universal": {517"configure_target": "sitl_periph_universal",518"waf_target": "bin/AP_Periph",519"default_params_filename": "default_params/periph.parm",520},521}522},523}524525526def default_frame(self, vehicle):527return self.options[vehicle]["default_frame"]528529def default_waf_target(self, vehicle):530"""Returns a waf target based on vehicle type, which is often determined by which directory the user is in"""531default_frame = self.default_frame(vehicle)532return self.options[vehicle]["frames"][default_frame]["waf_target"]533534def options_for_frame(self, frame, vehicle, opts):535"""Return information about how to sitl for frame e.g. build-type==sitl"""536ret = None537frames = self.options[vehicle]["frames"]538if frame in frames:539ret = self.options[vehicle]["frames"][frame]540else:541for p in ["octa", "tri", "y6", "firefly", "heli", "gazebo", "last_letter", "jsbsim", "quadplane", "plane-elevon", "plane-vtail", "plane", "airsim"]:542if frame.startswith(p):543ret = self.options[vehicle]["frames"][p]544break545if ret is None:546if frame.endswith("-heli"):547ret = self.options[vehicle]["frames"]["heli"]548if ret is None:549print("WARNING: no config for frame (%s)" % frame)550ret = {}551552if "model" not in ret:553ret["model"] = frame554555if "sitl-port" not in ret:556ret["sitl-port"] = True557558if opts.model is not None:559ret["model"] = opts.model560561if (ret["model"].find("xplane") != -1 or ret["model"].find("flightaxis") != -1):562ret["sitl-port"] = False563564565if "waf_target" not in ret:566ret["waf_target"] = self.default_waf_target(vehicle)567568if opts.build_target is not None:569ret["waf_target"] = opts.build_target570571return ret572573574575576577