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