Tools: sim_vehicle.py: print possible frame types in help message

This commit is contained in:
Peter Barker 2017-02-20 11:33:55 +11:00
parent dd9de7dfb5
commit fec23f6abe

View File

@ -19,6 +19,7 @@ import signal
import subprocess import subprocess
import sys import sys
import tempfile import tempfile
import textwrap
import time import time
import shlex import shlex
@ -37,8 +38,56 @@ class CompatError(Exception):
class CompatOptionParser(optparse.OptionParser): class CompatOptionParser(optparse.OptionParser):
"""An option parser which emulates the behaviour of the old sim_vehicle.sh; if passed -C, the first argument not understood starts a list of arguments that are passed straight to mavproxy""" """An option parser which emulates the behaviour of the old sim_vehicle.sh; if passed -C, the first argument not understood starts a list of arguments that are passed straight to mavproxy"""
class CustomFormatter(optparse.IndentedHelpFormatter):
def __init__(self, *args, **kwargs): def __init__(self, *args, **kwargs):
optparse.OptionParser.__init__(self, *args, **kwargs) optparse.IndentedHelpFormatter.__init__(self,*args, **kwargs)
# taken and modified from from optparse.py's format_option
def format_option_preserve_nl(self, option):
# The help for each option consists of two parts:
# * the opt strings and metavars
# eg. ("-x", or "-fFILENAME, --file=FILENAME")
# * the user-supplied help string
# eg. ("turn on expert mode", "read data from FILENAME")
#
# If possible, we write both of these on the same line:
# -x turn on expert mode
#
# But if the opt string list is too long, we put the help
# string on a second line, indented to the same column it would
# start in if it fit on the first line.
# -fFILENAME, --file=FILENAME
# read data from FILENAME
result = []
opts = self.option_strings[option]
opt_width = self.help_position - self.current_indent - 2
if len(opts) > opt_width:
opts = "%*s%s\n" % (self.current_indent, "", opts)
indent_first = self.help_position
else: # start help on same line as opts
opts = "%*s%-*s " % (self.current_indent, "", opt_width, opts)
indent_first = 0
result.append(opts)
if option.help:
help_text = self.expand_default(option)
tw = textwrap.TextWrapper(replace_whitespace=False, initial_indent="", subsequent_indent=" ", width=self.help_width)
for line in help_text.split("\n"):
help_lines = tw.wrap(line)
for line in help_lines:
result.extend(["%*s%s\n" % (self.help_position, "", line)])
elif opts[-1] != "\n":
result.append("\n")
return "".join(result)
def format_option(self, option):
if str(option).find('frame') != -1:
return self.format_option_preserve_nl(option)
return optparse.IndentedHelpFormatter.format_option(self, option)
def __init__(self, *args, **kwargs):
formatter = CompatOptionParser.CustomFormatter()
optparse.OptionParser.__init__(self, *args, formatter=formatter, **kwargs)
def error(self, error): def error(self, error):
"""Override default error handler called by optparse.OptionParser.parse_args when a parse error occurs; raise a detailed exception which can be caught""" """Override default error handler called by optparse.OptionParser.parse_args when a parse error occurs; raise a detailed exception which can be caught"""
@ -158,10 +207,12 @@ def kill_tasks():
'runsim.py', 'runsim.py',
'AntennaTracker.elf', 'AntennaTracker.elf',
} }
for frame in _options_for_frame.keys(): for vehicle in _options:
if "waf_target" not in _options_for_frame[frame]: for frame in _options[vehicle]["frames"]:
frame_info = _options[vehicle]["frames"][frame]
if "waf_target" not in frame_info:
continue continue
exe_name = os.path.basename(_options_for_frame[frame]["waf_target"]) exe_name = os.path.basename(frame_info["waf_target"])
victim_names.add(exe_name) victim_names.add(exe_name)
if under_cygwin(): if under_cygwin():
@ -229,10 +280,9 @@ make_target: option passed to make to create binaries. Usually sitl, and "-debu
default_params_filename: filename of default parameters file. Taken to be relative to autotest dir. 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 extra_mavlink_cmds: extra parameters that will be passed to mavproxy
""" """
_options_for_frame = { _options = {
"calibration": { "ArduCopter": {
"extra_mavlink_cmds": "module load sitl_calibration;", "frames": {
},
# COPTER # COPTER
"+": { "+": {
"waf_target": "bin/arducopter", "waf_target": "bin/arducopter",
@ -275,14 +325,18 @@ _options_for_frame = {
"waf_target": "bin/arducopter", "waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter-y6.parm", "default_params_filename": "default_params/copter-y6.parm",
}, },
# COPTER TYPES "firefly": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/firefly.parm",
},
# SIM
"IrisRos": { "IrisRos": {
"waf_target": "bin/arducopter", "waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter.parm", "default_params_filename": "default_params/copter.parm",
}, },
"firefly": { "gazebo-iris": {
"waf_target": "bin/arduplane", "waf_target": "bin/arducopter",
"default_params_filename": "default_params/firefly.parm", "default_params_filename": "default_params/gazebo-iris.parm",
}, },
# HELICOPTER # HELICOPTER
"heli": { "heli": {
@ -308,6 +362,13 @@ _options_for_frame = {
"waf_target": "bin/arducopter", "waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter-coax.parm", "default_params_filename": "default_params/copter-coax.parm",
}, },
"calibration": {
"extra_mavlink_cmds": "module load sitl_calibration;",
},
},
},
"ArduPlane": {
"frames": {
# PLANE # PLANE
"quadplane-tilttri": { "quadplane-tilttri": {
"make_target": "sitl", "make_target": "sitl",
@ -344,26 +405,6 @@ _options_for_frame = {
"waf_target": "bin/arduplane", "waf_target": "bin/arduplane",
"default_params_filename": "default_params/plane.parm", "default_params_filename": "default_params/plane.parm",
}, },
# 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-skid.parm",
},
# SUB
"sub": {
"model": "vectored",
"waf_target": "bin/ardusub",
"default_params_filename": "default_params/sub.parm",
},
# SIM
"gazebo-iris": {
"waf_target": "bin/arducopter",
"default_params_filename": "default_params/gazebo-iris.parm",
},
"gazebo-zephyr": { "gazebo-zephyr": {
"waf_target": "bin/arduplane", "waf_target": "bin/arduplane",
"default_params_filename": "default_params/gazebo-zephyr.parm", "default_params_filename": "default_params/gazebo-zephyr.parm",
@ -378,6 +419,35 @@ _options_for_frame = {
"waf_target": "bin/arduplane", "waf_target": "bin/arduplane",
"default_params_filename": "default_params/plane-jsbsim.parm", "default_params_filename": "default_params/plane-jsbsim.parm",
}, },
"calibration": {
"extra_mavlink_cmds": "module load sitl_calibration;",
},
},
},
"APMrover2": {
"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-skid.parm",
},
"calibration": {
"extra_mavlink_cmds": "module load sitl_calibration;",
},
},
},
"ArduSub": {
"frames": {
"vectored": {
"waf_target": "bin/ardusub",
"default_params_filename": "default_params/sub.parm",
},
},
},
} }
_default_waf_target = { _default_waf_target = {
@ -397,16 +467,17 @@ def default_waf_target(vehicle):
def options_for_frame(frame, vehicle, opts): def options_for_frame(frame, vehicle, opts):
"""Return informatiom about how to sitl for frame e.g. build-type==sitl""" """Return informatiom about how to sitl for frame e.g. build-type==sitl"""
ret = None ret = None
if frame in _options_for_frame: frames = _options[vehicle]["frames"]
ret = _options_for_frame[frame] if frame in frames:
ret = _options[vehicle]["frames"][frame]
else: else:
for p in ["octa", "tri", "y6", "firefly", "heli", "gazebo", "last_letter", "jsbsim", "quadplane", "plane-elevon", "plane-vtail", "plane"]: for p in ["octa", "tri", "y6", "firefly", "heli", "gazebo", "last_letter", "jsbsim", "quadplane", "plane-elevon", "plane-vtail", "plane"]:
if frame.startswith(p): if frame.startswith(p):
ret = _options_for_frame[p] ret = _options[vehicle]["frames"][p]
break break
if ret is None: if ret is None:
if frame.endswith("-heli"): if frame.endswith("-heli"):
ret = _options_for_frame["heli"] ret = _options[vehicle]["frames"]["heli"]
if ret is None: if ret is None:
ret = {} ret = {}
@ -731,7 +802,14 @@ default_frame_for_vehicle = {
"ArduSub": "vectored", "ArduSub": "vectored",
"AntennaTracker": "tracker", "AntennaTracker": "tracker",
} }
vehicle_options_string = '|'.join(default_frame_for_vehicle.keys()) vehicle_options_string = '|'.join(_options.keys())
def generate_frame_help():
ret = ""
for vehicle in _options:
frame_options_string = '|'.join(_options[vehicle]["frames"].keys())
ret += "%s: %s\n" % (vehicle, frame_options_string)
return ret
# define and run parser # define and run parser
parser = CompatOptionParser("sim_vehicle.py", parser = CompatOptionParser("sim_vehicle.py",
@ -742,9 +820,9 @@ parser = CompatOptionParser("sim_vehicle.py",
"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=default_frame_for_vehicle.keys())
parser.add_option("-f", "--frame", type='string', default=None, help="""set aircraft frame type parser.add_option("-f", "--frame", type='string', default=None, help="""set vehicle frame type
for copters can choose +, X, quad or octa
for planes can choose elevon or vtail""") %s""" % (generate_frame_help()))
parser.add_option("-C", "--sim_vehicle_sh_compatible", action='store_true', default=False, help="be compatible with the way sim_vehicle.sh works; make this the first option") parser.add_option("-C", "--sim_vehicle_sh_compatible", action='store_true', default=False, help="be compatible with the way sim_vehicle.sh works; make this the first option")
parser.add_option("-H", "--hil", action='store_true', default=False, help="start HIL") parser.add_option("-H", "--hil", action='store_true', default=False, help="start HIL")