param_metadata: fixed parameter parsing for multi-parameter objects
also adds more error checking
This commit is contained in:
parent
59b6118a1d
commit
5818dce3d2
@ -25,7 +25,12 @@ known_param_fields = [
|
||||
'User',
|
||||
]
|
||||
|
||||
required_param_fields = [
|
||||
'Description',
|
||||
'DisplayName',
|
||||
'User'
|
||||
]
|
||||
|
||||
known_group_fields = [
|
||||
'Path',
|
||||
'DisplayName',
|
||||
]
|
||||
'Path'
|
||||
]
|
||||
|
@ -1,47 +1,65 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
import os, glob, re
|
||||
import os, glob, re, sys
|
||||
|
||||
from param import *
|
||||
from wikiemit import WikiEmit
|
||||
from xmlemit import XmlEmit
|
||||
|
||||
from optparse import OptionParser
|
||||
parser = OptionParser("param_parse.py [options]")
|
||||
parser.add_option("-v", "--verbose", dest='verbose', action='store_true', default=False, help="show debugging output")
|
||||
parser.add_option("--vehicle", default='*', help="Vehicle type to generate for")
|
||||
(opts, args) = parser.parse_args()
|
||||
|
||||
|
||||
# Regular expressions for parsing the parameter metadata
|
||||
|
||||
prog_param = re.compile(r"@Param:\s*(\w+).*((?:\n\s*//\s*@(\w+): (.*))+)\s*G", re.MULTILINE)
|
||||
prog_param = re.compile(r"@Param: *(\w+).*((?:\n[ \t]*// @(\w+): (.*))+)(?:\n\n|\n[ \t]+[A-Z])", re.MULTILINE)
|
||||
|
||||
prog_param_fields = re.compile(r"\s*//\s*@(\w+): (.*)")
|
||||
prog_param_fields = re.compile(r"[ \t]*// @(\w+): (.*)")
|
||||
|
||||
prog_groups = re.compile(r"@Group:\s*(\w+).*((?:\n\s*//\s*@(\w+): (.*))+)\s*G", re.MULTILINE)
|
||||
prog_groups = re.compile(r"@Group: *(\w+).*((?:\n[ \t]*// @(Path): (\S+))+)", re.MULTILINE)
|
||||
|
||||
prog_group_param = re.compile(r"@Param:\s*(\w+).*((?:\n\s*//\s*@(\w+): (.*))+)\s*AP_", re.MULTILINE)
|
||||
prog_group_param = re.compile(r"@Param: (\w+).*((?:\n[ \t]*// @(\w+): (.*))+)(?:\n\n|\n[ \t]+[A-Z])", re.MULTILINE)
|
||||
|
||||
apm_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../')
|
||||
vehicle_paths = glob.glob(apm_path + "*/Parameters.pde")
|
||||
vehicle_paths = glob.glob(apm_path + "%s/Parameters.pde" % opts.vehicle)
|
||||
vehicle_paths.sort(reverse=True)
|
||||
|
||||
vehicles = []
|
||||
libraries = []
|
||||
|
||||
error_count = 0
|
||||
|
||||
def debug(str):
|
||||
'''debug output if verbose is set'''
|
||||
if opts.verbose:
|
||||
print(str)
|
||||
|
||||
def error(str):
|
||||
'''show errors'''
|
||||
global error_count
|
||||
error_count += 1
|
||||
print(str)
|
||||
|
||||
for vehicle_path in vehicle_paths:
|
||||
name = os.path.basename(os.path.dirname(vehicle_path))
|
||||
path = os.path.normpath(os.path.dirname(vehicle_path))
|
||||
vehicles.append(Vehicle(name, path))
|
||||
#print 'Added %s at %s' % (name, path)
|
||||
debug('Found vehicle type %s' % name)
|
||||
|
||||
for vehicle in vehicles:
|
||||
print "===\n\n\nProcessing %s" % vehicle.name
|
||||
debug("===\n\n\nProcessing %s" % vehicle.name)
|
||||
|
||||
f = open(vehicle.path+'/Parameters.pde')
|
||||
p_text = f.read()
|
||||
f.close()
|
||||
|
||||
|
||||
f.close()
|
||||
|
||||
param_matches = prog_param.findall(p_text)
|
||||
group_matches = prog_groups.findall(p_text)
|
||||
|
||||
print group_matches
|
||||
debug(group_matches)
|
||||
for group_match in group_matches:
|
||||
l = Library(group_match[0])
|
||||
fields = prog_param_fields.findall(group_match[1])
|
||||
@ -49,7 +67,7 @@ for vehicle in vehicles:
|
||||
if field[0] in known_group_fields:
|
||||
setattr(l, field[0], field[1])
|
||||
else:
|
||||
print "unknown parameter metadata field %s" % field[0]
|
||||
error("unknown parameter metadata field '%s'" % field[0])
|
||||
if l not in libraries:
|
||||
libraries.append(l)
|
||||
|
||||
@ -57,32 +75,35 @@ for vehicle in vehicles:
|
||||
|
||||
for param_match in param_matches:
|
||||
p = Parameter(vehicle.name+":"+param_match[0])
|
||||
print p.name + ' '
|
||||
debug(p.name + ' ')
|
||||
field_text = param_match[1]
|
||||
#print "\n\nParameter: %s\n" % p.name
|
||||
fields = prog_param_fields.findall(field_text)
|
||||
field_list = []
|
||||
for field in fields:
|
||||
field_list.append(field[0])
|
||||
if field[0] in known_param_fields:
|
||||
# #print " %s: %s" % (field[0], field[1])
|
||||
setattr(p, field[0], field[1])
|
||||
else:
|
||||
print "unknown parameter metadata field %s" % field[0]
|
||||
error("unknown parameter metadata field '%s'" % field[0])
|
||||
for req_field in required_param_fields:
|
||||
if not req_field in field_list:
|
||||
error("missing parameter metadata field '%s' in %s" % (req_field, field_text))
|
||||
|
||||
|
||||
vehicle.params.append(p)
|
||||
|
||||
##print vehicle.__dict__
|
||||
print "Processed %u params" % len(vehicle.params)
|
||||
debug("Processed %u params" % len(vehicle.params))
|
||||
|
||||
print "Found %u documented libraries" % len(libraries)
|
||||
debug("Found %u documented libraries" % len(libraries))
|
||||
|
||||
for library in libraries:
|
||||
print "===\n\n\nProcessing library %s" % library.name
|
||||
debug("===\n\n\nProcessing library %s" % library.name)
|
||||
|
||||
if hasattr(library, 'Path'):
|
||||
paths = library.Path.split(',')
|
||||
for path in paths:
|
||||
path = path.strip()
|
||||
print "\n Processing file %s" % path
|
||||
debug("\n Processing file %s" % path)
|
||||
libraryfname = os.path.normpath(os.path.join(apm_path + '/libraries/' + path))
|
||||
if path and os.path.exists(libraryfname):
|
||||
f = open(libraryfname)
|
||||
@ -90,26 +111,23 @@ for library in libraries:
|
||||
f.close()
|
||||
|
||||
param_matches = prog_group_param.findall(p_text)
|
||||
print "Found %u documented parameters" % len(param_matches)
|
||||
debug("Found %u documented parameters" % len(param_matches))
|
||||
for param_match in param_matches:
|
||||
p = Parameter(library.name+param_match[0])
|
||||
print p.name + ' '
|
||||
debug(p.name + ' ')
|
||||
field_text = param_match[1]
|
||||
# #print "\n\nParameter: %s\n" % p.name
|
||||
fields = prog_param_fields.findall(field_text)
|
||||
for field in fields:
|
||||
if field[0] in known_param_fields:
|
||||
# #print " %s: %s" % (field[0], field[1])
|
||||
setattr(p, field[0], field[1])
|
||||
else:
|
||||
print "unknown parameter metadata field %s" % field[0]
|
||||
error("unknown parameter metadata field %s" % field[0])
|
||||
|
||||
##print p.__dict__
|
||||
library.params.append(p)
|
||||
else:
|
||||
print "Skipped: no Path found"
|
||||
error("Skipped: no Path found")
|
||||
|
||||
print "Processed %u documented parameters" % len(library.params)
|
||||
debug("Processed %u documented parameters" % len(library.params))
|
||||
|
||||
def do_emit(emit):
|
||||
for vehicle in vehicles:
|
||||
@ -126,5 +144,4 @@ for library in libraries:
|
||||
do_emit(XmlEmit())
|
||||
do_emit(WikiEmit())
|
||||
|
||||
|
||||
|
||||
sys.exit(error_count)
|
||||
|
Loading…
Reference in New Issue
Block a user