Tools: sim_vehicle.py: move metadata into _options
This centralises configuration information in _options and removes duplication of data
This commit is contained in:
parent
fec23f6abe
commit
3be8c1e70b
@ -282,6 +282,7 @@ extra_mavlink_cmds: extra parameters that will be passed to mavproxy
|
|||||||
"""
|
"""
|
||||||
_options = {
|
_options = {
|
||||||
"ArduCopter": {
|
"ArduCopter": {
|
||||||
|
"default_frame": "quad",
|
||||||
"frames": {
|
"frames": {
|
||||||
# COPTER
|
# COPTER
|
||||||
"+": {
|
"+": {
|
||||||
@ -368,6 +369,7 @@ _options = {
|
|||||||
},
|
},
|
||||||
},
|
},
|
||||||
"ArduPlane": {
|
"ArduPlane": {
|
||||||
|
"default_frame": "jsbsim",
|
||||||
"frames": {
|
"frames": {
|
||||||
# PLANE
|
# PLANE
|
||||||
"quadplane-tilttri": {
|
"quadplane-tilttri": {
|
||||||
@ -425,6 +427,7 @@ _options = {
|
|||||||
},
|
},
|
||||||
},
|
},
|
||||||
"APMrover2": {
|
"APMrover2": {
|
||||||
|
"default_frame": "rover",
|
||||||
"frames": {
|
"frames": {
|
||||||
# ROVER
|
# ROVER
|
||||||
"rover": {
|
"rover": {
|
||||||
@ -441,6 +444,7 @@ _options = {
|
|||||||
},
|
},
|
||||||
},
|
},
|
||||||
"ArduSub": {
|
"ArduSub": {
|
||||||
|
"default_frame": "vectored",
|
||||||
"frames": {
|
"frames": {
|
||||||
"vectored": {
|
"vectored": {
|
||||||
"waf_target": "bin/ardusub",
|
"waf_target": "bin/ardusub",
|
||||||
@ -448,20 +452,20 @@ _options = {
|
|||||||
},
|
},
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
|
"AntennaTracker": {
|
||||||
|
"default_frame": "tracker",
|
||||||
|
"frames": {
|
||||||
|
"tracker": {
|
||||||
|
"waf_target": "bin/antennatracker",
|
||||||
|
},
|
||||||
|
},
|
||||||
|
},
|
||||||
}
|
}
|
||||||
|
|
||||||
_default_waf_target = {
|
|
||||||
"ArduPlane": "bin/arduplane",
|
|
||||||
"ArduCopter": "bin/arducopter",
|
|
||||||
"ArduSub": "bin/ardusub",
|
|
||||||
"APMrover2": "bin/ardurover",
|
|
||||||
"AntennaTracker": "bin/antennatracker",
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
def default_waf_target(vehicle):
|
def default_waf_target(vehicle):
|
||||||
"""Returns a waf target based on vehicle type, which is often determined by which directory the user is in"""
|
"""Returns a waf target based on vehicle type, which is often determined by which directory the user is in"""
|
||||||
return _default_waf_target[vehicle]
|
default_frame = _options[vehicle]["default_frame"]
|
||||||
|
return _options[vehicle]["frames"][default_frame]["waf_target"]
|
||||||
|
|
||||||
|
|
||||||
def options_for_frame(frame, vehicle, opts):
|
def options_for_frame(frame, vehicle, opts):
|
||||||
@ -671,9 +675,8 @@ def start_antenna_tracker(autotest, opts):
|
|||||||
progress("Preparing antenna tracker")
|
progress("Preparing antenna tracker")
|
||||||
tracker_home = find_location_by_name(find_autotest_dir(), opts.tracker_location)
|
tracker_home = find_location_by_name(find_autotest_dir(), opts.tracker_location)
|
||||||
vehicledir = os.path.join(autotest, "../../" + "AntennaTracker")
|
vehicledir = os.path.join(autotest, "../../" + "AntennaTracker")
|
||||||
tracker_frame_options = {
|
tracker_default_frame = _options["AntennaTracker"]["default_frame"]
|
||||||
"waf_target": _default_waf_target["AntennaTracker"],
|
tracker_frame_options = _options["AntennaTracker"]["frames"][tracker_default_frame]
|
||||||
}
|
|
||||||
do_build(vehicledir, opts, tracker_frame_options)
|
do_build(vehicledir, opts, tracker_frame_options)
|
||||||
tracker_instance = 1
|
tracker_instance = 1
|
||||||
os.chdir(vehicledir)
|
os.chdir(vehicledir)
|
||||||
@ -794,14 +797,6 @@ def start_mavproxy(opts, stuff):
|
|||||||
progress("MAVProxy exited")
|
progress("MAVProxy exited")
|
||||||
|
|
||||||
|
|
||||||
# determine a frame type if not specified:
|
|
||||||
default_frame_for_vehicle = {
|
|
||||||
"APMrover2": "rover",
|
|
||||||
"ArduPlane": "jsbsim",
|
|
||||||
"ArduCopter": "quad",
|
|
||||||
"ArduSub": "vectored",
|
|
||||||
"AntennaTracker": "tracker",
|
|
||||||
}
|
|
||||||
vehicle_options_string = '|'.join(_options.keys())
|
vehicle_options_string = '|'.join(_options.keys())
|
||||||
|
|
||||||
def generate_frame_help():
|
def generate_frame_help():
|
||||||
@ -819,7 +814,7 @@ parser = CompatOptionParser("sim_vehicle.py",
|
|||||||
"you are simulating, for example, start in the ArduPlane directory to " \
|
"you are simulating, for example, start in the ArduPlane directory to " \
|
||||||
"simulate ArduPlane")
|
"simulate ArduPlane")
|
||||||
|
|
||||||
parser.add_option("-v", "--vehicle", type='choice', default=None, help="vehicle type (%s)" % vehicle_options_string, choices=default_frame_for_vehicle.keys())
|
parser.add_option("-v", "--vehicle", type='choice', default=None, help="vehicle type (%s)" % vehicle_options_string, choices=_options.keys())
|
||||||
parser.add_option("-f", "--frame", type='string', default=None, help="""set vehicle frame type
|
parser.add_option("-f", "--frame", type='string', default=None, help="""set vehicle frame type
|
||||||
|
|
||||||
%s""" % (generate_frame_help()))
|
%s""" % (generate_frame_help()))
|
||||||
@ -909,20 +904,20 @@ if cmd_opts.vehicle is None:
|
|||||||
cwd = os.getcwd()
|
cwd = os.getcwd()
|
||||||
cmd_opts.vehicle = os.path.basename(cwd)
|
cmd_opts.vehicle = os.path.basename(cwd)
|
||||||
|
|
||||||
if cmd_opts.vehicle not in default_frame_for_vehicle:
|
if cmd_opts.vehicle not in _options:
|
||||||
# try in parent directories, useful for having config in subdirectories
|
# try in parent directories, useful for having config in subdirectories
|
||||||
cwd = os.getcwd()
|
cwd = os.getcwd()
|
||||||
while cwd:
|
while cwd:
|
||||||
bname = os.path.basename(cwd)
|
bname = os.path.basename(cwd)
|
||||||
if not bname:
|
if not bname:
|
||||||
break
|
break
|
||||||
if bname in default_frame_for_vehicle:
|
if bname in _options:
|
||||||
cmd_opts.vehicle = bname
|
cmd_opts.vehicle = bname
|
||||||
break
|
break
|
||||||
cwd = os.path.dirname(cwd)
|
cwd = os.path.dirname(cwd)
|
||||||
|
|
||||||
# try to validate vehicle
|
# try to validate vehicle
|
||||||
if cmd_opts.vehicle not in default_frame_for_vehicle:
|
if cmd_opts.vehicle not in _options:
|
||||||
progress('''
|
progress('''
|
||||||
** Is (%s) really your vehicle type?
|
** Is (%s) really your vehicle type?
|
||||||
Perhaps you could try -v %s
|
Perhaps you could try -v %s
|
||||||
@ -932,7 +927,7 @@ You could also try changing directory to e.g. the ArduCopter subdirectory
|
|||||||
|
|
||||||
# determine frame options (e.g. build type might be "sitl")
|
# determine frame options (e.g. build type might be "sitl")
|
||||||
if cmd_opts.frame is None:
|
if cmd_opts.frame is None:
|
||||||
cmd_opts.frame = default_frame_for_vehicle[cmd_opts.vehicle]
|
cmd_opts.frame = _options[cmd_opts.vehicle]["default_frame"]
|
||||||
|
|
||||||
# setup ports for this instance
|
# setup ports for this instance
|
||||||
mavlink_port = "tcp:127.0.0.1:" + str(5760 + 10 * cmd_opts.instance)
|
mavlink_port = "tcp:127.0.0.1:" + str(5760 + 10 * cmd_opts.instance)
|
||||||
|
Loading…
Reference in New Issue
Block a user