mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Tools: make apm.pdef.xml more readable.
This commit is contained in:
parent
16469e703e
commit
774c8583b1
@ -5,22 +5,27 @@ from xml.sax.saxutils import escape, quoteattr
|
|||||||
from emit import Emit
|
from emit import Emit
|
||||||
from param import known_param_fields, known_units
|
from param import known_param_fields, known_units
|
||||||
|
|
||||||
|
INDENT2 = " "
|
||||||
|
INDENT4 = " "
|
||||||
|
INDENT6 = " "
|
||||||
|
INDENT8 = " "
|
||||||
|
INDENT10 = " "
|
||||||
|
|
||||||
# Emit APM documentation in an machine readable XML format
|
# Emit APM documentation in an machine readable XML format
|
||||||
class XmlEmit(Emit):
|
class XmlEmit(Emit):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
Emit.__init__(self)
|
Emit.__init__(self)
|
||||||
wiki_fname = 'apm.pdef.xml'
|
self.wiki_fname = 'apm.pdef.xml'
|
||||||
self.f = open(wiki_fname, mode='w')
|
self.f = open(self.wiki_fname, mode='w')
|
||||||
preamble = '''<?xml version="1.0" encoding="utf-8"?>
|
self.preamble = '''<?xml version="1.0" encoding="utf-8"?>
|
||||||
<!-- Dynamically generated list of documented parameters (generated by param_parse.py) -->
|
<!-- Dynamically generated list of documented parameters (generated by param_parse.py) -->
|
||||||
<paramfile>
|
'''
|
||||||
<vehicles>
|
self.f.write(self.preamble)
|
||||||
'''
|
self.f.write('''<paramfile>
|
||||||
self.f.write(preamble)
|
<vehicles>\n''')
|
||||||
|
|
||||||
def close(self):
|
def close(self):
|
||||||
self.f.write('</libraries>')
|
self.f.write(INDENT2 + '</libraries>\n')
|
||||||
self.f.write('''</paramfile>\n''')
|
self.f.write('''</paramfile>\n''')
|
||||||
self.f.close()
|
self.f.close()
|
||||||
|
|
||||||
@ -28,18 +33,18 @@ class XmlEmit(Emit):
|
|||||||
self.f.write("<!-- " + s + " -->")
|
self.f.write("<!-- " + s + " -->")
|
||||||
|
|
||||||
def start_libraries(self):
|
def start_libraries(self):
|
||||||
self.f.write('</vehicles>')
|
self.f.write(INDENT2 + '</vehicles>\n')
|
||||||
self.f.write('<libraries>')
|
self.f.write(INDENT2 + '<libraries>\n')
|
||||||
|
|
||||||
def emit(self, g):
|
def emit(self, g):
|
||||||
t = '''<parameters name=%s>\n''' % quoteattr(g.name) # i.e. ArduPlane
|
t = INDENT4 + '''<parameters name=%s>\n''' % quoteattr(g.name) # i.e. ArduPlane
|
||||||
|
|
||||||
for param in g.params:
|
for param in g.params:
|
||||||
# Begin our parameter node
|
# Begin our parameter node
|
||||||
if hasattr(param, 'DisplayName'):
|
if hasattr(param, 'DisplayName'):
|
||||||
t += '<param humanName=%s name=%s' % (quoteattr(param.DisplayName), quoteattr(param.name)) # i.e. ArduPlane (ArduPlane:FOOPARM)
|
t += INDENT6 + '<param humanName=%s name=%s' % (quoteattr(param.DisplayName), quoteattr(param.name)) # i.e. ArduPlane (ArduPlane:FOOPARM)
|
||||||
else:
|
else:
|
||||||
t += '<param name=%s' % quoteattr(param.name)
|
t += INDENT6 + '<param name=%s' % quoteattr(param.name)
|
||||||
|
|
||||||
if hasattr(param, 'Description'):
|
if hasattr(param, 'Description'):
|
||||||
t += ' documentation=%s' % quoteattr(param.Description) # i.e. parameter docs
|
t += ' documentation=%s' % quoteattr(param.Description) # i.e. parameter docs
|
||||||
@ -55,27 +60,27 @@ class XmlEmit(Emit):
|
|||||||
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'] 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]):
|
||||||
t += "<values>\n"
|
t += INDENT8 + "<values>\n"
|
||||||
|
|
||||||
values = (param.__dict__[field]).split(',')
|
values = (param.__dict__[field]).split(',')
|
||||||
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)
|
||||||
t += '''<value code=%s>%s</value>\n''' % (quoteattr(v[0]), escape(v[1])) # i.e. numeric value, string label
|
t += INDENT10 + '''<value code=%s>%s</value>\n''' % (quoteattr(v[0]), escape(v[1])) # i.e. numeric value, string label
|
||||||
|
|
||||||
t += "</values>\n"
|
t += INDENT8 + "</values>\n"
|
||||||
elif field == 'Units':
|
elif field == 'Units':
|
||||||
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 += '''<field name=%s>%s</field>\n''' % (quoteattr(field), escape(abreviated_units)) # i.e. A/s
|
t += INDENT8 + '''<field name=%s>%s</field>\n''' % (quoteattr(field), escape(abreviated_units)) # i.e. A/s
|
||||||
t += '''<field name=%s>%s</field>\n''' % (quoteattr('UnitText'), escape(units)) # i.e. ampere per second
|
t += INDENT8 + '''<field name=%s>%s</field>\n''' % (quoteattr('UnitText'), escape(units)) # i.e. ampere per second
|
||||||
else:
|
else:
|
||||||
t += '''<field name=%s>%s</field>\n''' % (quoteattr(field), escape(param.__dict__[field])) # i.e. Range: 0 10
|
t += INDENT8 + '''<field name=%s>%s</field>\n''' % (quoteattr(field), escape(param.__dict__[field])) # i.e. Range: 0 10
|
||||||
|
|
||||||
t += '''</param>\n'''
|
t += INDENT6 + '''</param>\n'''
|
||||||
t += '''</parameters>\n'''
|
t += INDENT4 + '''</parameters>\n'''
|
||||||
|
|
||||||
# print t
|
# print t
|
||||||
self.f.write(t)
|
self.f.write(t)
|
||||||
|
Loading…
Reference in New Issue
Block a user