mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Tools: updated for new param fields
This commit is contained in:
parent
9790aae49c
commit
097ef85598
@ -5,7 +5,7 @@ Emit docs in a form acceptable to the old Ardupilot wordpress docs site
|
|||||||
|
|
||||||
from param import known_param_fields, known_units
|
from param import known_param_fields, known_units
|
||||||
from emit import Emit
|
from emit import Emit
|
||||||
import cgi
|
import html
|
||||||
|
|
||||||
|
|
||||||
class HtmlEmit(Emit):
|
class HtmlEmit(Emit):
|
||||||
@ -59,7 +59,7 @@ DO NOT EDIT
|
|||||||
t += '\n\n<h2>%s</h2>' % tag
|
t += '\n\n<h2>%s</h2>' % tag
|
||||||
if d.get('User', None) == 'Advanced':
|
if d.get('User', None) == 'Advanced':
|
||||||
t += '<em>Note: This parameter is for advanced users</em><br>'
|
t += '<em>Note: This parameter is for advanced users</em><br>'
|
||||||
t += "\n\n<p>%s</p>\n" % cgi.escape(param.Description)
|
t += "\n\n<p>%s</p>\n" % html.escape(param.Description)
|
||||||
t += "<ul>\n"
|
t += "<ul>\n"
|
||||||
|
|
||||||
for field in param.__dict__.keys():
|
for field in param.__dict__.keys():
|
||||||
@ -77,8 +77,8 @@ DO NOT EDIT
|
|||||||
abreviated_units = param.__dict__[field]
|
abreviated_units = param.__dict__[field]
|
||||||
if abreviated_units != '':
|
if abreviated_units != '':
|
||||||
units = known_units[abreviated_units] # use the known_units dictionary to convert the abreviated unit into a full textual one
|
units = known_units[abreviated_units] # use the known_units dictionary to convert the abreviated unit into a full textual one
|
||||||
t += "<li>%s: %s</li>\n" % (field, cgi.escape(units))
|
t += "<li>%s: %s</li>\n" % (field, html.escape(units))
|
||||||
else:
|
else:
|
||||||
t += "<li>%s: %s</li>\n" % (field, cgi.escape(param.__dict__[field]))
|
t += "<li>%s: %s</li>\n" % (field, html.escape(param.__dict__[field]))
|
||||||
t += "</ul>\n"
|
t += "</ul>\n"
|
||||||
self.t += t
|
self.t += t
|
||||||
|
103
Tools/autotest/param_metadata/jsonemit.py
Normal file
103
Tools/autotest/param_metadata/jsonemit.py
Normal file
@ -0,0 +1,103 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
import json
|
||||||
|
import copy
|
||||||
|
from emit import Emit
|
||||||
|
|
||||||
|
|
||||||
|
# Emit APM documentation in JSON format
|
||||||
|
class JSONEmit(Emit):
|
||||||
|
def __init__(self):
|
||||||
|
Emit.__init__(self)
|
||||||
|
json_fname = 'apm.pdef.json'
|
||||||
|
self.f = open(json_fname, mode='w')
|
||||||
|
self.content = {"json": {"version": 0}}
|
||||||
|
self.name = ''
|
||||||
|
|
||||||
|
def close(self):
|
||||||
|
json.dump(self.content, self.f, indent=2, sort_keys=True)
|
||||||
|
self.f.close()
|
||||||
|
|
||||||
|
def jsonFromKeyList(self, main_key, dictionary):
|
||||||
|
json_object = {}
|
||||||
|
if main_key in dictionary:
|
||||||
|
values = dictionary[main_key]
|
||||||
|
for value in values.split(','):
|
||||||
|
key, description = value.split(":")
|
||||||
|
json_object[key.strip()] = description.strip()
|
||||||
|
return json_object
|
||||||
|
|
||||||
|
def emit(self, g):
|
||||||
|
content = {}
|
||||||
|
|
||||||
|
# Copy content to avoid any modification
|
||||||
|
g = copy.deepcopy(g)
|
||||||
|
|
||||||
|
# Get vehicle name
|
||||||
|
if 'truename' in g.__dict__:
|
||||||
|
self.name = g.__dict__['truename']
|
||||||
|
self.content[self.name] = {}
|
||||||
|
|
||||||
|
# Check all params available
|
||||||
|
for param in g.params:
|
||||||
|
param_json = {}
|
||||||
|
|
||||||
|
# Get display name
|
||||||
|
if hasattr(param, 'DisplayName'):
|
||||||
|
# i.e. ArduPlane (ArduPlane:FOOPARM)
|
||||||
|
param_json['displayName'] = param.DisplayName
|
||||||
|
|
||||||
|
# Get description
|
||||||
|
if hasattr(param, 'Description'):
|
||||||
|
param_json['description'] = param.Description
|
||||||
|
|
||||||
|
# Get user type
|
||||||
|
if hasattr(param, 'User'):
|
||||||
|
# i.e. Standard or Advanced
|
||||||
|
param_json['user'] = param.User
|
||||||
|
|
||||||
|
# Get param name and and remove key
|
||||||
|
name = param.__dict__.pop('name')
|
||||||
|
if ':' in name:
|
||||||
|
name = name.split(':')[1]
|
||||||
|
|
||||||
|
# Remove real_path key
|
||||||
|
if 'real_path' in param.__dict__:
|
||||||
|
param.__dict__.pop('real_path')
|
||||||
|
|
||||||
|
# Get range section if available
|
||||||
|
range_json = {}
|
||||||
|
if 'Range' in param.__dict__:
|
||||||
|
range = param.__dict__['Range'].split(' ')
|
||||||
|
range_json['low'] = range[0]
|
||||||
|
range_json['high'] = range[1]
|
||||||
|
param.__dict__.pop('Range')
|
||||||
|
|
||||||
|
# Get bitmask section if available
|
||||||
|
bitmask_json = self.jsonFromKeyList('Bitmask', param.__dict__)
|
||||||
|
if(bitmask_json):
|
||||||
|
param.__dict__.pop('Bitmask')
|
||||||
|
|
||||||
|
# get value section if availables
|
||||||
|
values_json = self.jsonFromKeyList('Values', param.__dict__)
|
||||||
|
if(values_json):
|
||||||
|
param.__dict__.pop('Values')
|
||||||
|
|
||||||
|
# Set actual content
|
||||||
|
content[name] = param.__dict__
|
||||||
|
|
||||||
|
# Set range if available
|
||||||
|
if(range_json):
|
||||||
|
content[name]['Range'] = range_json
|
||||||
|
|
||||||
|
# Set bitmask if available
|
||||||
|
if(bitmask_json):
|
||||||
|
content[name]['Bitmask'] = bitmask_json
|
||||||
|
|
||||||
|
# Set values if available
|
||||||
|
if(values_json):
|
||||||
|
content[name]['Values'] = values_json
|
||||||
|
|
||||||
|
# Update main content with actual content
|
||||||
|
for key in content:
|
||||||
|
self.content[self.name][key] = content[key]
|
@ -31,6 +31,7 @@ known_param_fields = [
|
|||||||
'Bitmask',
|
'Bitmask',
|
||||||
'Volatile',
|
'Volatile',
|
||||||
'ReadOnly',
|
'ReadOnly',
|
||||||
|
'Calibration',
|
||||||
]
|
]
|
||||||
|
|
||||||
# Follow SI units conventions from:
|
# Follow SI units conventions from:
|
||||||
|
@ -13,6 +13,7 @@ from rstemit import RSTEmit
|
|||||||
from wikiemit import WikiEmit
|
from wikiemit import WikiEmit
|
||||||
from xmlemit import XmlEmit
|
from xmlemit import XmlEmit
|
||||||
from mdemit import MDEmit
|
from mdemit import MDEmit
|
||||||
|
from jsonemit import JSONEmit
|
||||||
|
|
||||||
parser = ArgumentParser(description="Parse ArduPilot parameters.")
|
parser = ArgumentParser(description="Parse ArduPilot parameters.")
|
||||||
parser.add_argument("-v", "--verbose", dest='verbose', action='store_true', default=False, help="show debugging output")
|
parser.add_argument("-v", "--verbose", dest='verbose', action='store_true', default=False, help="show debugging output")
|
||||||
@ -26,19 +27,19 @@ parser.add_argument("--format",
|
|||||||
dest='output_format',
|
dest='output_format',
|
||||||
action='store',
|
action='store',
|
||||||
default='all',
|
default='all',
|
||||||
choices=['all', 'html', 'rst', 'wiki', 'xml', 'edn', 'md'],
|
choices=['all', 'html', 'rst', 'wiki', 'xml', 'json', 'edn', 'md'],
|
||||||
help="what output format to use")
|
help="what output format to use")
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
|
|
||||||
|
|
||||||
# Regular expressions for parsing the parameter metadata
|
# Regular expressions for parsing the parameter metadata
|
||||||
|
|
||||||
prog_param = re.compile(r"@Param: (\w+).*((?:\n[ \t]*// @(\w+)(?:{([^}]+)})?: (.*))+)(?:\n\n|\n[ \t]+[A-Z])", re.MULTILINE)
|
prog_param = re.compile(r"@Param: (\w+).*((?:\n[ \t]*// @(\w+)(?:{([^}]+)})?: (.*))+)(?:\n[ \t\r]*\n|\n[ \t]+[A-Z])", re.MULTILINE)
|
||||||
|
|
||||||
# match e.g @Value: 0=Unity, 1=Koala, 17=Liability
|
# match e.g @Value: 0=Unity, 1=Koala, 17=Liability
|
||||||
prog_param_fields = re.compile(r"[ \t]*// @(\w+): (.*)")
|
prog_param_fields = re.compile(r"[ \t]*// @(\w+): ([^\r\n]*)")
|
||||||
# match e.g @Value{Copter}: 0=Volcano, 1=Peppermint
|
# match e.g @Value{Copter}: 0=Volcano, 1=Peppermint
|
||||||
prog_param_tagged_fields = re.compile(r"[ \t]*// @(\w+){([^}]+)}: (.*)")
|
prog_param_tagged_fields = re.compile(r"[ \t]*// @(\w+){([^}]+)}: ([^\r\n]*)")
|
||||||
|
|
||||||
prog_groups = re.compile(r"@Group: *(\w+).*((?:\n[ \t]*// @(Path): (\S+))+)", re.MULTILINE)
|
prog_groups = re.compile(r"@Group: *(\w+).*((?:\n[ \t]*// @(Path): (\S+))+)", re.MULTILINE)
|
||||||
|
|
||||||
@ -53,6 +54,12 @@ vehicle_paths.sort(reverse=True)
|
|||||||
vehicles = []
|
vehicles = []
|
||||||
libraries = []
|
libraries = []
|
||||||
|
|
||||||
|
# AP_Vehicle also has parameters rooted at "", but isn't referenced
|
||||||
|
# from the vehicle in any way:
|
||||||
|
ap_vehicle_lib = Library("") # the "" is tacked onto the front of param name
|
||||||
|
setattr(ap_vehicle_lib, "Path", os.path.join('..', 'libraries', 'AP_Vehicle', 'AP_Vehicle.cpp'))
|
||||||
|
libraries.append(ap_vehicle_lib)
|
||||||
|
|
||||||
error_count = 0
|
error_count = 0
|
||||||
current_param = None
|
current_param = None
|
||||||
current_file = None
|
current_file = None
|
||||||
@ -69,14 +76,14 @@ def error(str_to_print):
|
|||||||
global error_count
|
global error_count
|
||||||
error_count += 1
|
error_count += 1
|
||||||
if current_file is not None:
|
if current_file is not None:
|
||||||
print("In %s" % current_file)
|
print("Error in %s" % current_file)
|
||||||
if current_param is not None:
|
if current_param is not None:
|
||||||
print("At param %s" % current_param)
|
print("At param %s" % current_param)
|
||||||
print(str_to_print)
|
print(str_to_print)
|
||||||
|
|
||||||
|
|
||||||
truename_map = {
|
truename_map = {
|
||||||
"APMrover2": "Rover",
|
"Rover": "Rover",
|
||||||
"ArduSub": "Sub",
|
"ArduSub": "Sub",
|
||||||
"ArduCopter": "Copter",
|
"ArduCopter": "Copter",
|
||||||
"ArduPlane": "Plane",
|
"ArduPlane": "Plane",
|
||||||
@ -124,7 +131,7 @@ for vehicle in vehicles:
|
|||||||
for field in fields:
|
for field in fields:
|
||||||
field_list.append(field[0])
|
field_list.append(field[0])
|
||||||
if field[0] in known_param_fields:
|
if field[0] in known_param_fields:
|
||||||
value = re.sub('@PREFIX@', "", field[1])
|
value = re.sub('@PREFIX@', "", field[1]).rstrip()
|
||||||
setattr(p, field[0], value)
|
setattr(p, field[0], value)
|
||||||
else:
|
else:
|
||||||
error("param: unknown parameter metadata field '%s'" % field[0])
|
error("param: unknown parameter metadata field '%s'" % field[0])
|
||||||
@ -165,7 +172,7 @@ def process_library(vehicle, library, pathprefix=None):
|
|||||||
p_text = f.read()
|
p_text = f.read()
|
||||||
f.close()
|
f.close()
|
||||||
else:
|
else:
|
||||||
error("Path %s not found for library %s" % (path, library.name))
|
error("Path %s not found for library %s (fname=%s)" % (path, library.name, libraryfname))
|
||||||
continue
|
continue
|
||||||
|
|
||||||
param_matches = prog_param.findall(p_text)
|
param_matches = prog_param.findall(p_text)
|
||||||
@ -278,7 +285,8 @@ def validate(param):
|
|||||||
if (hasattr(param, "Range")):
|
if (hasattr(param, "Range")):
|
||||||
rangeValues = param.__dict__["Range"].split(" ")
|
rangeValues = param.__dict__["Range"].split(" ")
|
||||||
if (len(rangeValues) != 2):
|
if (len(rangeValues) != 2):
|
||||||
error("Invalid Range values for %s" % (param.name))
|
error("Invalid Range values for %s (%s)" %
|
||||||
|
(param.name, param.__dict__["Range"]))
|
||||||
return
|
return
|
||||||
min_value = rangeValues[0]
|
min_value = rangeValues[0]
|
||||||
max_value = rangeValues[1]
|
max_value = rangeValues[1]
|
||||||
@ -288,6 +296,15 @@ def validate(param):
|
|||||||
if not is_number(max_value):
|
if not is_number(max_value):
|
||||||
error("Max value not number: %s %s" % (param.name, max_value))
|
error("Max value not number: %s %s" % (param.name, max_value))
|
||||||
return
|
return
|
||||||
|
# Check for duplicate in @value field
|
||||||
|
if (hasattr(param, "Values")):
|
||||||
|
valueList = param.__dict__["Values"].split(",")
|
||||||
|
values = []
|
||||||
|
for i in valueList:
|
||||||
|
i = i.replace(" ","")
|
||||||
|
values.append(i.partition(":")[0])
|
||||||
|
if (len(values) != len(set(values))):
|
||||||
|
print("Duplicate values found")
|
||||||
# Validate units
|
# Validate units
|
||||||
if (hasattr(param, "Units")):
|
if (hasattr(param, "Units")):
|
||||||
if (param.__dict__["Units"] != "") and (param.__dict__["Units"] not in known_units):
|
if (param.__dict__["Units"] != "") and (param.__dict__["Units"] not in known_units):
|
||||||
@ -335,6 +352,8 @@ def do_emit(emit):
|
|||||||
|
|
||||||
|
|
||||||
if args.emit_params:
|
if args.emit_params:
|
||||||
|
if args.output_format == 'all' or args.output_format == 'json':
|
||||||
|
do_emit(JSONEmit())
|
||||||
if args.output_format == 'all' or args.output_format == 'xml':
|
if args.output_format == 'all' or args.output_format == 'xml':
|
||||||
do_emit(XmlEmit())
|
do_emit(XmlEmit())
|
||||||
if args.output_format == 'all' or args.output_format == 'wiki':
|
if args.output_format == 'all' or args.output_format == 'wiki':
|
||||||
|
@ -3,7 +3,7 @@ from __future__ import print_function
|
|||||||
import re
|
import re
|
||||||
from param import known_param_fields, known_units
|
from param import known_param_fields, known_units
|
||||||
from emit import Emit
|
from emit import Emit
|
||||||
import cgi
|
import html
|
||||||
|
|
||||||
|
|
||||||
# Emit docs in a RST format
|
# Emit docs in a RST format
|
||||||
@ -241,7 +241,7 @@ Complete Parameter List
|
|||||||
|
|
||||||
headings = []
|
headings = []
|
||||||
row = []
|
row = []
|
||||||
for field in param.__dict__.keys():
|
for field in sorted(param.__dict__.keys()):
|
||||||
if field not in ['name', 'DisplayName', 'Description', 'User'] and field in known_param_fields:
|
if field not in ['name', 'DisplayName', 'Description', 'User'] and field in known_param_fields:
|
||||||
headings.append(field)
|
headings.append(field)
|
||||||
if field in field_table_info and Emit.prog_values_field.match(param.__dict__[field]):
|
if field in field_table_info and Emit.prog_values_field.match(param.__dict__[field]):
|
||||||
@ -256,9 +256,9 @@ Complete Parameter List
|
|||||||
# convert the abreviated unit into a full
|
# convert the abreviated unit into a full
|
||||||
# textual one:
|
# textual one:
|
||||||
units = known_units[abreviated_units]
|
units = known_units[abreviated_units]
|
||||||
row.append(cgi.escape(units))
|
row.append(html.escape(units))
|
||||||
else:
|
else:
|
||||||
row.append(cgi.escape(param.__dict__[field]))
|
row.append(html.escape(param.__dict__[field]))
|
||||||
if len(row):
|
if len(row):
|
||||||
ret += "\n\n" + self.tablify([row], headings=headings) + "\n\n"
|
ret += "\n\n" + self.tablify([row], headings=headings) + "\n\n"
|
||||||
self.t += ret + "\n"
|
self.t += ret + "\n"
|
||||||
|
@ -46,6 +46,9 @@ class XmlEmit(Emit):
|
|||||||
if hasattr(param, 'User'):
|
if hasattr(param, 'User'):
|
||||||
t += ' user=%s' % quoteattr(param.User) # i.e. Standard or Advanced
|
t += ' user=%s' % quoteattr(param.User) # i.e. Standard or Advanced
|
||||||
|
|
||||||
|
if hasattr(param, 'Calibration'):
|
||||||
|
t += ' calibration=%s' % quoteattr(param.Calibration) # i.e. Standard or Advanced
|
||||||
|
|
||||||
t += ">\n"
|
t += ">\n"
|
||||||
|
|
||||||
# Add values as chidren of this node
|
# Add values as chidren of this node
|
||||||
|
Loading…
Reference in New Issue
Block a user