Tools: param_parse.py: sort RCn_OPTIONS progamatically
This commit is contained in:
parent
0154277989
commit
e7cd43ad86
@ -65,7 +65,7 @@ DO NOT EDIT
|
|||||||
t += "<ul>\n"
|
t += "<ul>\n"
|
||||||
|
|
||||||
for field in param.__dict__.keys():
|
for field in 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', 'SortValues'] and field in known_param_fields:
|
||||||
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
||||||
values = (param.__dict__[field]).split(',')
|
values = (param.__dict__[field]).split(',')
|
||||||
t += "<table><th>Value</th><th>Meaning</th>\n"
|
t += "<table><th>Value</th><th>Meaning</th>\n"
|
||||||
|
@ -55,9 +55,12 @@ class JSONEmit(Emit):
|
|||||||
if ':' in name:
|
if ':' in name:
|
||||||
name = name.split(':')[1]
|
name = name.split(':')[1]
|
||||||
|
|
||||||
# Remove real_path key
|
# Remove various unwanted keys
|
||||||
if 'real_path' in param.__dict__:
|
for key in 'real_path', 'SortValues':
|
||||||
param.__dict__.pop('real_path')
|
try:
|
||||||
|
param.__dict__.pop(key)
|
||||||
|
except KeyError:
|
||||||
|
pass
|
||||||
|
|
||||||
# Get range section if available
|
# Get range section if available
|
||||||
range_json = {}
|
range_json = {}
|
||||||
|
@ -90,7 +90,7 @@ class MDEmit(Emit):
|
|||||||
t += "\n\n%s" % param.Description
|
t += "\n\n%s" % param.Description
|
||||||
|
|
||||||
for field in param.__dict__.keys():
|
for field in 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', 'SortValues'] and field in known_param_fields:
|
||||||
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
||||||
values = (param.__dict__[field]).split(',')
|
values = (param.__dict__[field]).split(',')
|
||||||
t += "\n\n|Value|Meaning|"
|
t += "\n\n|Value|Meaning|"
|
||||||
|
@ -51,6 +51,7 @@ known_param_fields = [
|
|||||||
'ReadOnly',
|
'ReadOnly',
|
||||||
'Calibration',
|
'Calibration',
|
||||||
'Vector3Parameter',
|
'Vector3Parameter',
|
||||||
|
'SortValues'
|
||||||
]
|
]
|
||||||
|
|
||||||
# Follow SI units conventions from:
|
# Follow SI units conventions from:
|
||||||
|
@ -263,7 +263,7 @@ This list is automatically generated from the latest ardupilot source code, and
|
|||||||
headings = []
|
headings = []
|
||||||
row = []
|
row = []
|
||||||
for field in sorted(param.__dict__.keys()):
|
for field in sorted(param.__dict__.keys()):
|
||||||
if (field not in ['name', 'DisplayName', 'Description', 'User', 'RebootRequired'] and
|
if (field not in ['name', 'DisplayName', 'Description', 'User', 'SortValues', 'RebootRequired'] and
|
||||||
field in known_param_fields):
|
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]):
|
||||||
|
@ -2,6 +2,7 @@ from lxml import etree
|
|||||||
|
|
||||||
from emit import Emit
|
from emit import Emit
|
||||||
from param import known_param_fields, known_units
|
from param import known_param_fields, known_units
|
||||||
|
import re
|
||||||
|
|
||||||
# Emit ArduPilot documentation in an machine readable XML format
|
# Emit ArduPilot documentation in an machine readable XML format
|
||||||
class XmlEmit(Emit):
|
class XmlEmit(Emit):
|
||||||
@ -30,6 +31,18 @@ class XmlEmit(Emit):
|
|||||||
def start_libraries(self):
|
def start_libraries(self):
|
||||||
self.current_element = self.libraries
|
self.current_element = self.libraries
|
||||||
|
|
||||||
|
def sorted_Values_keys(self, nv_pairs, zero_at_top=False):
|
||||||
|
'''sorts name/value pairs derived from items in @Values. Sorts by
|
||||||
|
value, with special attention paid to common "Do nothing" values'''
|
||||||
|
keys = nv_pairs.keys()
|
||||||
|
def sort_key(value):
|
||||||
|
description = nv_pairs[value]
|
||||||
|
if zero_at_top and value == "0":
|
||||||
|
# make sure this item goes at the top of the list:
|
||||||
|
return "AAAAAAA"
|
||||||
|
return description
|
||||||
|
return sorted(keys, key=sort_key)
|
||||||
|
|
||||||
def emit(self, g):
|
def emit(self, g):
|
||||||
xml_parameters = etree.SubElement(self.current_element, 'parameters', name=g.reference) # i.e. ArduPlane
|
xml_parameters = etree.SubElement(self.current_element, 'parameters', name=g.reference) # i.e. ArduPlane
|
||||||
|
|
||||||
@ -50,17 +63,36 @@ class XmlEmit(Emit):
|
|||||||
|
|
||||||
# Add values as chidren of this node
|
# Add values as chidren of this node
|
||||||
for field in param.__dict__.keys():
|
for field in 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', 'SortValues'] and field in known_param_fields:
|
||||||
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
if field == 'Values' and Emit.prog_values_field.match(param.__dict__[field]):
|
||||||
xml_values = etree.SubElement(xml_param, 'values')
|
xml_values = etree.SubElement(xml_param, 'values')
|
||||||
values = (param.__dict__[field]).split(',')
|
values = (param.__dict__[field]).split(',')
|
||||||
|
nv_unsorted = {}
|
||||||
for value in values:
|
for value in values:
|
||||||
v = value.split(':')
|
v = value.split(':')
|
||||||
if len(v) != 2:
|
if len(v) != 2:
|
||||||
raise ValueError("Bad value (%s)" % v)
|
raise ValueError("Bad value (%s)" % v)
|
||||||
# i.e. numeric value, string label
|
# i.e. numeric value, string label
|
||||||
xml_value = etree.SubElement(xml_values, 'value', code=v[0])
|
if v[0] in nv_unsorted:
|
||||||
xml_value.text = v[1]
|
raise ValueError("%s already exists" % v[0])
|
||||||
|
nv_unsorted[v[0]] = v[1]
|
||||||
|
|
||||||
|
all_keys = nv_unsorted.keys()
|
||||||
|
if hasattr(param, 'SortValues'):
|
||||||
|
sort = getattr(param, 'SortValues').lower()
|
||||||
|
zero_at_top = False
|
||||||
|
if sort == 'alphabeticalzeroattop':
|
||||||
|
zero_at_top = True
|
||||||
|
else:
|
||||||
|
raise ValueError("Unknown sort (%s)" % sort)
|
||||||
|
|
||||||
|
all_keys = self.sorted_Values_keys(nv_unsorted, zero_at_top=zero_at_top)
|
||||||
|
|
||||||
|
for key in all_keys:
|
||||||
|
value = nv_unsorted[key]
|
||||||
|
|
||||||
|
xml_value = etree.SubElement(xml_values, 'value', code=key)
|
||||||
|
xml_value.text = value
|
||||||
|
|
||||||
elif field == 'Units':
|
elif field == 'Units':
|
||||||
abreviated_units = param.__dict__[field]
|
abreviated_units = param.__dict__[field]
|
||||||
|
Loading…
Reference in New Issue
Block a user