simplify param scoping and centralize dependencies

This commit is contained in:
Daniel Agar
2017-11-21 00:44:23 -05:00
committed by ChristophTobler
parent e5cc1237e3
commit fc80846825
14 changed files with 23 additions and 30 deletions
+16 -12
View File
@@ -51,7 +51,10 @@ endif()
set(module_list)
if (DISABLE_PARAMS_MODULE_SCOPING)
# search all directories with .c files (potentially containing parameters)
file(GLOB_RECURSE new_list ${PX4_SOURCE_DIR}/src/*.c)
file(GLOB_RECURSE new_list
${PX4_SOURCE_DIR}/src/*.c
${external_module_paths}
)
foreach(file_path ${new_list})
get_filename_component(dir_path ${file_path} PATH)
list(APPEND module_list "${dir_path}")
@@ -61,17 +64,21 @@ else()
foreach(module ${config_module_list})
list(APPEND module_list ${PX4_SOURCE_DIR}/src/${module})
endforeach()
list(APPEND module_list
${external_module_paths}
)
endif()
set(parameters_xml ${PX4_BINARY_DIR}/parameters.xml)
file(GLOB_RECURSE param_src_files ${PX4_SOURCE_DIR}/src/*params.c)
add_custom_command(OUTPUT ${parameters_xml}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
-s ${module_list} ${EXTERNAL_MODULES_LOCATION}
--board CONFIG_ARCH_${BOARD} --xml --inject-xml
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_process_params.py
--src-path ${module_list}
--xml ${parameters_xml}
--inject-xml ${CMAKE_CURRENT_SOURCE_DIR}/parameters_injected.xml
--overrides ${PARAM_DEFAULT_OVERRIDES}
DEPENDS ${param_src_files} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
WORKING_DIRECTORY ${PX4_BINARY_DIR}
#--verbose
DEPENDS ${param_src_files} px_process_params.py parameters_injected.xml
COMMENT "Generating parameters.xml"
)
add_custom_target(parameters_xml DEPENDS ${parameters_xml})
@@ -82,12 +89,10 @@ add_custom_command(OUTPUT px4_parameters.c px4_parameters.h
--xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS
${PX4_BINARY_DIR}/parameters.xml
${CMAKE_CURRENT_SOURCE_DIR}/px_generate_params.py
${CMAKE_CURRENT_SOURCE_DIR}/templates/px4_parameters.c.jinja
${CMAKE_CURRENT_SOURCE_DIR}/templates/px4_parameters.h.jinja
px_generate_params.py
templates/px4_parameters.c.jinja
templates/px4_parameters.h.jinja
)
set_source_files_properties(px4_parameters.c PROPERTIES GENERATED TRUE)
set_source_files_properties(px4_parameters.h PROPERTIES GENERATED TRUE)
px4_add_module(
MODULE modules__systemlib__param
@@ -102,4 +107,3 @@ px4_add_module(
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
@@ -0,0 +1,138 @@
<?xml version='1.0' encoding='UTF-8'?>
<parameters>
<version>3</version>
<group name="UAVCAN Motor Parameters" no_code_generation="true">
<parameter default="75" name="ctl_bw" type="INT32">
<short_desc>Speed controller bandwidth</short_desc>
<long_desc>Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.</long_desc>
<unit>Hertz</unit>
<min>10</min>
<max>250</max>
</parameter>
<parameter default="1" name="ctl_dir" type="INT32">
<short_desc>Reverse direction</short_desc>
<long_desc>Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.</long_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="1" name="ctl_gain" type="FLOAT">
<short_desc>Speed (RPM) controller gain</short_desc>
<long_desc>Speed (RPM) controller gain. Determines controller
aggressiveness; units are amp-seconds per radian. Systems with
higher rotational inertia (large props) will need gain increased;
systems with low rotational inertia (small props) may need gain
decreased. Higher values result in faster response, but may result
in oscillation and excessive overshoot. Lower values result in a
slower, smoother response.</long_desc>
<unit>amp-seconds per radian</unit>
<decimal>3</decimal>
<min>0.00</min>
<max>1.00</max>
</parameter>
<parameter default="3.5" name="ctl_hz_idle" type="FLOAT">
<short_desc>Idle speed (e Hz)</short_desc>
<long_desc>Idle speed (e Hz)</long_desc>
<unit>Hertz</unit>
<decimal>3</decimal>
<min>0.0</min>
<max>100.0</max>
</parameter>
<parameter default="25" name="ctl_start_rate" type="INT32">
<short_desc>Spin-up rate (e Hz/s)</short_desc>
<long_desc>Spin-up rate (e Hz/s)</long_desc>
<unit>Hz/s</unit>
<min>5</min>
<max>1000</max>
</parameter>
<parameter default="0" name="esc_index" type="INT32">
<short_desc>Index of this ESC in throttle command messages.</short_desc>
<long_desc>Index of this ESC in throttle command messages.</long_desc>
<unit>Index</unit>
<min>0</min>
<max>15</max>
</parameter>
<parameter default="20034" name="id_ext_status" type="INT32">
<short_desc>Extended status ID</short_desc>
<long_desc>Extended status ID</long_desc>
<min>1</min>
<max>1000000</max>
</parameter>
<parameter default="50000" name="int_ext_status" type="INT32">
<short_desc>Extended status interval (µs)</short_desc>
<long_desc>Extended status interval (µs)</long_desc>
<unit>µs</unit>
<min>0</min>
<max>1000000</max>
</parameter>
<parameter default="50000" name="int_status" type="INT32">
<short_desc>ESC status interval (µs)</short_desc>
<long_desc>ESC status interval (µs)</long_desc>
<unit>µs</unit>
<max>1000000</max>
</parameter>
<parameter default="12" name="mot_i_max" type="FLOAT">
<short_desc>Motor current limit in amps</short_desc>
<long_desc>Motor current limit in amps. This determines the maximum
current controller setpoint, as well as the maximum allowable
current setpoint slew rate. This value should generally be set to
the continuous current rating listed in the motors specification
sheet, or set equal to the motors specified continuous power
divided by the motor voltage limit.</long_desc>
<unit>Amps</unit>
<decimal>3</decimal>
<min>1</min>
<max>80</max>
</parameter>
<parameter default="2300" name="mot_kv" type="INT32">
<short_desc>Motor Kv in RPM per volt</short_desc>
<long_desc>Motor Kv in RPM per volt. This can be taken from the motors
specification sheet; accuracy will help control performance but
some deviation from the specified value is acceptable.</long_desc>
<unit>RPM/v</unit>
<min>0</min>
<max>4000</max>
</parameter>
<parameter default="0.0" name="mot_ls" type="FLOAT">
<short_desc>READ ONLY: Motor inductance in henries.</short_desc>
<long_desc>READ ONLY: Motor inductance in henries. This is measured on start-up.</long_desc>
<unit>henries</unit>
<decimal>3</decimal>
</parameter>
<parameter default="14" name="mot_num_poles" type="INT32">
<short_desc>Number of motor poles.</short_desc>
<long_desc>Number of motor poles. Used to convert mechanical speeds to
electrical speeds. This number should be taken from the motors
specification sheet.</long_desc>
<unit>Poles</unit>
<min>2</min>
<max>40</max>
</parameter>
<parameter default="0.0" name="mot_rs" type="FLOAT">
<short_desc>READ ONLY: Motor resistance in ohms</short_desc>
<long_desc>READ ONLY: Motor resistance in ohms. This is measured on start-up. When
tuning a new motor, check that this value is approximately equal
to the value shown in the motors specification sheet.</long_desc>
<unit>Ohms</unit>
<decimal>3</decimal>
</parameter>
<parameter default="0.5" name="mot_v_accel" type="FLOAT">
<short_desc>Acceleration limit (V)</short_desc>
<long_desc>Acceleration limit (V)</long_desc>
<unit>Volts</unit>
<decimal>3</decimal>
<min>0.01</min>
<max>1.00</max>
</parameter>
<parameter default="14.8" name="mot_v_max" type="FLOAT">
<short_desc>Motor voltage limit in volts</short_desc>
<long_desc>Motor voltage limit in volts. The current controllers
commanded voltage will never exceed this value. Note that this may
safely be above the nominal voltage of the motor; to determine the
actual motor voltage limit, divide the motors rated power by the
motor current limit.</long_desc>
<unit>Volts</unit>
<decimal>3</decimal>
<min>0</min>
</parameter>
</group>
</parameters>
@@ -0,0 +1 @@
This folder contains a python library used by px_process_params.py
@@ -0,0 +1 @@
__all__ = ["srcscanner", "srcparser", "xmlout", "dokuwikiout", "dokuwikirpc", "scope"]
@@ -0,0 +1,44 @@
from xml.sax.saxutils import escape
import codecs
class DokuWikiTablesOutput():
def __init__(self, groups):
result = ("====== Parameter Reference ======\n"
"<note>**This list is auto-generated from the source code** and contains the most recent parameter documentation.</note>\n"
"\n")
for group in groups:
result += "==== %s ====\n\n" % group.GetName()
result += "|< 100% 25% 45% 10% 10% 10% >|\n"
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^\n"
result += "^ ::: ^ Comment ^^^^\n"
for param in group.GetParams():
code = param.GetName()
def_val = param.GetDefault()
name = param.GetFieldValue("short_desc")
min_val = param.GetFieldValue("min")
max_val = param.GetFieldValue("max")
long_desc = param.GetFieldValue("long_desc")
if name == code:
name = ""
else:
name = name.replace("\n", " ")
name = name.replace("|", "%%|%%")
name = name.replace("^", "%%^%%")
result += "| **%s** |" % code
result += " %s |" % name
result += " %s |" % (min_val or "")
result += " %s |" % (max_val or "")
result += " %s |" % (def_val or "")
result += "\n"
if long_desc is not None:
result += "| ::: | <div>%s</div> ||||\n" % long_desc
result += "\n"
self.output = result;
def Save(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
f.write(self.output)
@@ -0,0 +1,16 @@
try:
import xmlrpclib
except ImportError:
import xmlrpc.client as xmlrpclib
# See https://www.dokuwiki.org/devel:xmlrpc for a list of available functions!
# Usage example:
# xmlrpc = dokuwikirpc.get_xmlrpc(url, username, password)
# print(xmlrpc.dokuwiki.getVersion())
def get_xmlrpc(url, username, password):
#proto, url = url.split("://")
#url = proto + "://" + username + ":" + password + "@" + url + "/lib/exe/xmlrpc.php"
url += "/lib/exe/xmlrpc.php?u=" + username + "&p=" + password
return xmlrpclib.ServerProxy(url)
@@ -0,0 +1,105 @@
from xml.sax.saxutils import escape
import codecs
class MarkdownTablesOutput():
def __init__(self, groups):
result = ("# Parameter Reference\n"
"> **Note** **This list is auto-generated from the source code** and contains the most recent parameter documentation.\n"
"\n")
for group in groups:
result += '## %s\n\n' % group.GetName()
#Check if scope (module where parameter is defined) is the same for all parameters in the group.
# If so then display just once about the table.
scope_set = set()
for param in group.GetParams():
scope_set.add(param.GetFieldValue("scope"))
if len(scope_set)==1:
result+='\nThe module where these parameters are defined is: *%s*.\n\n' % list(scope_set)[0]
result += '<table style="width: 100%; table-layout:fixed; font-size:1.5rem;">\n'
result += ' <colgroup><col style="width: 23%"><col style="width: 46%"><col style="width: 11%"><col style="width: 11%"><col style="width: 9%"></colgroup>\n'
result += ' <thead>\n'
result += ' <tr><th>Name</th><th>Description</th><th>Min > Max (Incr.)</th><th>Default</th><th>Units</th></tr>\n'
result += ' </thead>\n'
result += '<tbody>\n'
for param in group.GetParams():
code = param.GetName()
name = param.GetFieldValue("short_desc") or ''
long_desc = param.GetFieldValue("long_desc") or ''
min_val = param.GetFieldValue("min") or ''
max_val = param.GetFieldValue("max") or ''
increment = param.GetFieldValue("increment") or ''
def_val = param.GetDefault() or ''
unit = param.GetFieldValue("unit") or ''
type = param.GetType()
reboot_required = param.GetFieldValue("reboot_required") or ''
#board = param.GetFieldValue("board") or '' ## Disabled as no board values are defined in any parameters!
#decimal = param.GetFieldValue("decimal") or '' #Disabled as is intended for GCS not people
#field_codes = param.GetFieldCodes() ## Disabled as not needed for display.
#boolean = param.GetFieldValue("boolean") # or '' # Disabled - does not appear useful.
# Format values for display.
# Display min/max/increment value based on what values are defined.
max_min_combined = ''
if min_val or max_val:
if not min_val:
min_val='?'
if not max_val:
max_val='?'
max_min_combined+='%s > %s ' % (min_val, max_val)
if increment:
max_min_combined+='(%s)' % increment
if long_desc is not '':
long_desc = '<p><strong>Comment:</strong> %s</p>' % long_desc
if name == code:
name = ""
code='<strong id="%s">%s</strong>' % (code, code)
if reboot_required:
reboot_required='<p><b>Reboot required:</b> %s</p>\n' % reboot_required
scope=''
if not len(scope_set)==1 or len(scope_set)==0:
scope = param.GetFieldValue("scope") or ''
if scope:
scope='<p><b>Module:</b> %s</p>\n' % scope
enum_codes=param.GetEnumCodes() or '' # Gets numerical values for parameter.
enum_output=''
# Format codes and their descriptions for display.
if enum_codes:
enum_output+='<strong>Values:</strong><ul>'
enum_codes=sorted(enum_codes,key=int)
for item in enum_codes:
enum_output+='\n<li><strong>%s:</strong> %s</li> \n' % (item, param.GetEnumValue(item))
enum_output+='</ul>\n'
bitmask_list=param.GetBitmaskList() #Gets bitmask values for parameter
bitmask_output=''
#Format bitmask values
if bitmask_list:
bitmask_output+='<strong>Bitmask:</strong><ul>'
for bit in bitmask_list:
bit_text = param.GetBitmaskBit(bit)
bitmask_output+=' <li><strong>%s:</strong> %s</li> \n' % (bit, bit_text)
bitmask_output+='</ul>\n'
result += '<tr>\n <td style="vertical-align: top;">%s (%s)</td>\n <td style="vertical-align: top;"><p>%s</p>%s %s %s %s %s</td>\n <td style="vertical-align: top;">%s</td>\n <td style="vertical-align: top;">%s </td>\n <td style="vertical-align: top;">%s</td>\n</tr>\n' % (code,type,name, long_desc, enum_output, bitmask_output, reboot_required, scope, max_min_combined,def_val,unit)
#Close the table.
result += '</tbody></table>\n\n'
self.output = result
def Save(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
f.write(self.output)
@@ -0,0 +1,32 @@
import os
import re
class Scope(object):
"""
Single parameter group
"""
re_deep_lines = re.compile(r'.*\/.*\/')
def __init__(self,):
self.scope = set()
def __str__(self):
return self.scope.__str__()
def Add(self, scope):
"""
Add Scope to set
"""
self.scope.add(scope)
def Has(self, scope):
"""
Check for existance
"""
if len(self.scope) == 0:
return True
# Anything in the form xxxxx/yyyyy/zzzzz....
# is treated as xxxxx/yyyyy
while (self.re_deep_lines.match(scope)):
scope = os.path.dirname(scope)
return scope in self.scope
@@ -0,0 +1,381 @@
import sys
import re
import math
global default_var
default_var = {}
class ParameterGroup(object):
"""
Single parameter group
"""
def __init__(self, name):
self.name = name
self.params = []
def AddParameter(self, param):
"""
Add parameter to the group
"""
self.params.append(param)
def GetName(self):
"""
Get parameter group name
"""
return self.name
def GetParams(self):
"""
Returns the parsed list of parameters. Every parameter is a Parameter
object. Note that returned object is not a copy. Modifications affect
state of the parser.
"""
return sorted(self.params,
key=lambda x: x.GetFieldValue("code"))
class Parameter(object):
"""
Single parameter
"""
# Define sorting order of the fields
priority = {
"board": 9,
"short_desc": 8,
"long_desc": 7,
"min": 5,
"max": 4,
"unit": 3,
"decimal": 2,
# all others == 0 (sorted alphabetically)
}
def __init__(self, name, type, default = ""):
self.fields = {}
self.values = {}
self.bitmask = {}
self.name = name
self.type = type
self.default = default
def GetName(self):
return self.name
def GetType(self):
return self.type
def GetDefault(self):
return self.default
def SetField(self, code, value):
"""
Set named field value
"""
self.fields[code] = value
def SetEnumValue(self, code, value):
"""
Set named enum value
"""
self.values[code] = value
def SetBitmaskBit(self, index, bit):
"""
Set named enum value
"""
self.bitmask[index] = bit
def GetFieldCodes(self):
"""
Return list of existing field codes in convenient order
"""
keys = self.fields.keys()
keys = sorted(keys)
keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True)
return keys
def GetFieldValue(self, code):
"""
Return value of the given field code or None if not found.
"""
fv = self.fields.get(code)
if not fv:
# required because python 3 sorted does not accept None
return ""
return fv
def GetEnumCodes(self):
"""
Return list of existing value codes in convenient order
"""
keys = self.values.keys()
#keys = sorted(keys)
#keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True)
return keys
def GetEnumValue(self, code):
"""
Return value of the given enum code or None if not found.
"""
fv = self.values.get(code)
if not fv:
# required because python 3 sorted does not accept None
return ""
return fv
def GetBitmaskList(self):
"""
Return list of existing bitmask codes in convenient order
"""
keys = self.bitmask.keys()
return sorted(keys, key=float)
def GetBitmaskBit(self, index):
"""
Return value of the given bitmask code or None if not found.
"""
fv = self.bitmask.get(index)
if not fv:
# required because python 3 sorted does not accept None
return ""
return fv
class SourceParser(object):
"""
Parses provided data and stores all found parameters internally.
"""
re_split_lines = re.compile(r'[\r\n]+')
re_comment_start = re.compile(r'^\/\*\*')
re_comment_content = re.compile(r'^\*\s*(.*)')
re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)')
re_comment_end = re.compile(r'(.*?)\s*\*\/')
re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;')
re_px4_parameter_definition = re.compile(r'PX4_PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*\)\s*;')
re_px4_param_default_definition = re.compile(r'#define\s*PARAM_([A-Z_][A-Z0-9_]*)\s*([^ ,\)]+)\s*')
re_cut_type_specifier = re.compile(r'[a-z]+$')
re_is_a_number = re.compile(r'^-?[0-9\.]')
re_remove_dots = re.compile(r'\.+$')
re_remove_carriage_return = re.compile('\n+')
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean", "bit"])
# Order of parameter groups
priority = {
# All other groups = 0 (sort alphabetically)
"Miscellaneous": -10
}
def __init__(self):
self.param_groups = {}
def Parse(self, scope, contents):
"""
Incrementally parse program contents and append all found parameters
to the list.
"""
# This code is essentially a comment-parsing grammar. "state"
# represents parser state. It contains human-readable state
# names.
state = None
for line in self.re_split_lines.split(contents):
line = line.strip()
# Ignore empty lines
if line == "":
continue
if self.re_comment_start.match(line):
state = "wait-short"
short_desc = None
long_desc = None
tags = {}
def_values = {}
def_bitmask = {}
elif state is not None and state != "comment-processed":
m = self.re_comment_end.search(line)
if m:
line = m.group(1)
last_comment_line = True
else:
last_comment_line = False
m = self.re_comment_content.match(line)
if m:
comment_content = m.group(1)
if comment_content == "":
# When short comment ends with empty comment line,
# start waiting for the next part - long comment.
if state == "wait-short-end":
state = "wait-long"
else:
m = self.re_comment_tag.match(comment_content)
if m:
tag, desc = m.group(1, 2)
if (tag == "value"):
# Take the meta info string and split the code and description
metainfo = desc.split(" ", 1)
def_values[metainfo[0]] = metainfo[1]
elif (tag == "bit"):
# Take the meta info string and split the code and description
metainfo = desc.split(" ", 1)
def_bitmask[metainfo[0]] = metainfo[1]
else:
tags[tag] = desc
current_tag = tag
state = "wait-tag-end"
elif state == "wait-short":
# Store first line of the short description
short_desc = comment_content
state = "wait-short-end"
elif state == "wait-short-end":
# Append comment line to the short description
short_desc += "\n" + comment_content
elif state == "wait-long":
# Store first line of the long description
long_desc = comment_content
state = "wait-long-end"
elif state == "wait-long-end":
# Append comment line to the long description
long_desc += "\n" + comment_content
elif state == "wait-tag-end":
# Append comment line to the tag text
tags[current_tag] += "\n" + comment_content
else:
raise AssertionError(
"Invalid parser state: %s" % state)
elif not last_comment_line:
# Invalid comment line (inside comment, but not starting with
# "*" or "*/". Reset parsed content.
state = None
if last_comment_line:
state = "comment-processed"
else:
tp = None
name = None
defval = ""
# Non-empty line outside the comment
m = self.re_px4_param_default_definition.match(line)
# Default value handling
if m:
name_m, defval_m = m.group(1,2)
default_var[name_m] = defval_m
m = self.re_parameter_definition.match(line)
if m:
tp, name, defval = m.group(1, 2, 3)
else:
m = self.re_px4_parameter_definition.match(line)
if m:
tp, name = m.group(1, 2)
if (name+'_DEFAULT') in default_var:
defval = default_var[name+'_DEFAULT']
if tp is not None:
# Remove trailing type specifier from numbers: 0.1f => 0.1
if defval != "" and self.re_is_a_number.match(defval):
defval = self.re_cut_type_specifier.sub('', defval)
param = Parameter(name, tp, defval)
param.SetField("scope", scope)
param.SetField("short_desc", name)
# If comment was found before the parameter declaration,
# inject its data into the newly created parameter.
group = "Miscellaneous"
if state == "comment-processed":
if short_desc is not None:
param.SetField("short_desc", self.re_remove_dots.sub('', short_desc))
if long_desc is not None:
long_desc = self.re_remove_carriage_return.sub(' ', long_desc)
param.SetField("long_desc", long_desc)
for tag in tags:
if tag == "group":
group = tags[tag]
elif tag not in self.valid_tags:
sys.stderr.write("Skipping invalid documentation tag: '%s'\n" % tag)
return False
else:
param.SetField(tag, tags[tag])
for def_value in def_values:
param.SetEnumValue(def_value, def_values[def_value])
for def_bit in def_bitmask:
param.SetBitmaskBit(def_bit, def_bitmask[def_bit])
# Store the parameter
if group not in self.param_groups:
self.param_groups[group] = ParameterGroup(group)
self.param_groups[group].AddParameter(param)
state = None
return True
def IsNumber(self, numberString):
try:
float(numberString)
return True
except ValueError:
return False
def Validate(self):
"""
Validates the parameter meta data.
"""
seenParamNames = []
for group in self.GetParamGroups():
for param in group.GetParams():
name = param.GetName()
if len(name) > 16:
sys.stderr.write("Parameter Name {0} is too long (Limit is 16)\n".format(name))
return False
board = param.GetFieldValue("board")
# Check for duplicates
name_plus_board = name + "+" + board
for seenParamName in seenParamNames:
if seenParamName == name_plus_board:
sys.stderr.write("Duplicate parameter definition: {0}\n".format(name_plus_board))
return False
seenParamNames.append(name_plus_board)
# Validate values
default = param.GetDefault()
min = param.GetFieldValue("min")
max = param.GetFieldValue("max")
#sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max))
if default != "" and not self.IsNumber(default):
sys.stderr.write("Default value not number: {0} {1}\n".format(name, default))
return False
if min != "":
if not self.IsNumber(min):
sys.stderr.write("Min value not number: {0} {1}\n".format(name, min))
return False
if default != "" and float(default) < float(min):
sys.stderr.write("Default value is smaller than min: {0} default:{1} min:{2}\n".format(name, default, min))
return False
if max != "":
if not self.IsNumber(max):
sys.stderr.write("Max value not number: {0} {1}\n".format(name, max))
return False
if default != "" and float(default) > float(max):
sys.stderr.write("Default value is larger than max: {0} default:{1} max:{2}\n".format(name, default, max))
return False
for code in param.GetEnumCodes():
if not self.IsNumber(code):
sys.stderr.write("Min value not number: {0} {1}\n".format(name, code))
return False
if param.GetEnumValue(code) == "":
sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code))
return False
for index in param.GetBitmaskList():
if not self.IsNumber(index):
sys.stderr.write("bit value not number: {0} {1}\n".format(name, index))
return False
if not int(min) <= math.pow(2, int(index)) <= int(max):
sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index))))
return False
if param.GetBitmaskBit(index) == "":
sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index))
return False
return True
def GetParamGroups(self):
"""
Returns the parsed list of parameters. Every parameter is a Parameter
object. Note that returned object is not a copy. Modifications affect
state of the parser.
"""
groups = self.param_groups.values()
groups = sorted(groups, key=lambda x: x.GetName())
groups = sorted(groups, key=lambda x: self.priority.get(x.GetName(), 0), reverse=True)
return groups
@@ -0,0 +1,50 @@
import os
import re
import codecs
import sys
class SourceScanner(object):
"""
Traverses directory tree, reads all source files, and passes their contents
to the Parser.
"""
def ScanDir(self, srcdirs, parser):
"""
Scans provided path and passes all found contents to the parser using
parser.Parse method.
"""
extensions1 = tuple([".h"])
extensions2 = tuple([".c"])
for srcdir in srcdirs:
for filename in os.listdir(srcdir):
if filename.endswith(extensions1):
path = os.path.join(srcdir, filename)
if not self.ScanFile(path, parser):
return False
for filename in os.listdir(srcdir):
if filename.endswith(extensions2):
path = os.path.join(srcdir, filename)
if not self.ScanFile(path, parser):
return False
return True
def ScanFile(self, path, parser):
"""
Scans provided file and passes its contents to the parser using
parser.Parse method.
"""
# Extract the scope: it is the directory within the repo. Either it
# starts directly with 'src/module/abc', or it has the form 'x/y/z/src/module/abc'.
# The output is 'module/abc' in both cases.
prefix = "^(|.*" + os.path.sep + ")src" + os.path.sep
scope = re.sub(prefix.replace("\\", "/"), "", os.path.dirname(os.path.relpath(path)).replace("\\", "/"))
with codecs.open(path, 'r', 'utf-8') as f:
try:
contents = f.read()
except:
contents = ''
print('Failed reading file: %s, skipping content.' % path)
pass
return parser.Parse(scope, contents)
@@ -0,0 +1,78 @@
import xml.etree.ElementTree as ET
import codecs
def indent(elem, level=0):
i = "\n" + level*" "
if len(elem):
if not elem.text or not elem.text.strip():
elem.text = i + " "
if not elem.tail or not elem.tail.strip():
elem.tail = i
for elem in elem:
indent(elem, level+1)
if not elem.tail or not elem.tail.strip():
elem.tail = i
else:
if level and (not elem.tail or not elem.tail.strip()):
elem.tail = i
class XMLOutput():
def __init__(self, groups, board, inject_xml_file_name):
xml_parameters = ET.Element("parameters")
xml_version = ET.SubElement(xml_parameters, "version")
xml_version.text = "3"
xml_version = ET.SubElement(xml_parameters, "parameter_version_major")
xml_version.text = "1"
xml_version = ET.SubElement(xml_parameters, "parameter_version_minor")
xml_version.text = "15"
importtree = ET.parse(inject_xml_file_name)
injectgroups = importtree.getroot().findall("group")
for igroup in injectgroups:
xml_parameters.append(igroup)
last_param_name = ""
board_specific_param_set = False
for group in groups:
xml_group = ET.SubElement(xml_parameters, "group")
xml_group.attrib["name"] = group.GetName()
for param in group.GetParams():
if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName():
xml_param = ET.SubElement(xml_group, "parameter")
xml_param.attrib["name"] = param.GetName()
xml_param.attrib["default"] = param.GetDefault()
xml_param.attrib["type"] = param.GetType()
last_param_name = param.GetName()
for code in param.GetFieldCodes():
value = param.GetFieldValue(code)
if code == "board":
if value == board:
board_specific_param_set = True
xml_field = ET.SubElement(xml_param, code)
xml_field.text = value
else:
xml_group.remove(xml_param)
else:
xml_field = ET.SubElement(xml_param, code)
xml_field.text = value
if last_param_name != param.GetName():
board_specific_param_set = False
if len(param.GetEnumCodes()) > 0:
xml_values = ET.SubElement(xml_param, "values")
for code in param.GetEnumCodes():
xml_value = ET.SubElement(xml_values, "value")
xml_value.attrib["code"] = code;
xml_value.text = param.GetEnumValue(code)
if len(param.GetBitmaskList()) > 0:
xml_values = ET.SubElement(xml_param, "bitmask")
for index in param.GetBitmaskList():
xml_value = ET.SubElement(xml_values, "bit")
xml_value.attrib["index"] = index;
xml_value.text = param.GetBitmaskBit(index)
indent(xml_parameters)
self.xml_document = ET.ElementTree(xml_parameters)
def Save(self, filename):
self.xml_document.write(filename, encoding="UTF-8")
+200
View File
@@ -0,0 +1,200 @@
#!/usr/bin/env python
############################################################################
#
# Copyright (C) 2013-2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# PX4 paramers processor (main executable file)
#
# This tool scans the PX4 source code for declarations of tunable parameters
# and outputs the list in various formats.
#
# Currently supported formats are:
# * XML for the parametric UI generator
# * Human-readable description in DokuWiki page format
# * Human-readable description in Markdown page format for the PX4 dev guide
#
# This tool also allows to automatically upload the human-readable version
# to the DokuWiki installation via XML-RPC.
#
from __future__ import print_function
import sys
import os
import argparse
from px4params import srcscanner, srcparser, xmlout, dokuwikiout, dokuwikirpc, markdownout
import re
import json
import codecs
def main():
# Parse command line arguments
parser = argparse.ArgumentParser(description="Process parameter documentation.")
parser.add_argument("-s", "--src-path",
default=["../src"],
metavar="PATH",
nargs='*',
help="one or more paths to source files to scan for parameters")
parser.add_argument("-x", "--xml",
nargs='?',
const="parameters.xml",
metavar="FILENAME",
help="Create XML file"
" (default FILENAME: parameters.xml)")
parser.add_argument("-i", "--inject-xml",
nargs='?',
const="../Tools/parameters_injected.xml",
metavar="FILENAME",
help="Inject additional param XML file"
" (default FILENAME: ../Tools/parameters_injected.xml)")
parser.add_argument("-b", "--board",
nargs='?',
const="",
metavar="BOARD",
help="Board to create xml parameter xml for")
parser.add_argument("-m", "--markdown",
nargs='?',
const="parameters.md",
metavar="FILENAME",
help="Create Markdown file"
" (default FILENAME: parameters.md)")
parser.add_argument("-w", "--wiki",
nargs='?',
const="parameters.wiki",
metavar="FILENAME",
help="Create DokuWiki file"
" (default FILENAME: parameters.wiki)")
parser.add_argument("-u", "--wiki-update",
nargs='?',
const="firmware:parameters",
metavar="PAGENAME",
help="Update DokuWiki page"
" (default PAGENAME: firmware:parameters)")
parser.add_argument("--wiki-url",
default="https://pixhawk.org",
metavar="URL",
help="DokuWiki URL"
" (default: https://pixhawk.org)")
parser.add_argument("--wiki-user",
default=os.environ.get('XMLRPCUSER', None),
metavar="USERNAME",
help="DokuWiki XML-RPC user name"
" (default: $XMLRPCUSER environment variable)")
parser.add_argument("--wiki-pass",
default=os.environ.get('XMLRPCPASS', None),
metavar="PASSWORD",
help="DokuWiki XML-RPC user password"
" (default: $XMLRPCUSER environment variable)")
parser.add_argument("--wiki-summary",
metavar="SUMMARY",
default="Automagically updated parameter documentation from code.",
help="DokuWiki page edit summary")
parser.add_argument('-v', '--verbose',
action='store_true',
help="verbose output")
parser.add_argument("-o", "--overrides",
default="{}",
metavar="OVERRIDES",
help="a dict of overrides in the form of a json string")
args = parser.parse_args()
# Check for valid command
if not (args.xml or args.wiki or args.wiki_update or args.markdown):
print("Error: You need to specify at least one output method!\n")
parser.print_usage()
sys.exit(1)
# Initialize source scanner and parser
scanner = srcscanner.SourceScanner()
parser = srcparser.SourceParser()
# Scan directories, and parse the files
if (args.verbose):
print("Scanning source path " + str(args.src_path))
if not scanner.ScanDir(args.src_path, parser):
sys.exit(1)
if not parser.Validate():
sys.exit(1)
param_groups = parser.GetParamGroups()
if len(param_groups) == 0:
print("Warning: no parameters found")
override_dict = json.loads(args.overrides)
if len(override_dict.keys()) > 0:
for group in param_groups:
for param in group.GetParams():
name = param.GetName()
if name in override_dict.keys():
val = str(override_dict[param.GetName()])
param.default = val
print("OVERRIDING {:s} to {:s}!!!!!".format(name, val))
# Output to XML file
if args.xml:
if args.verbose:
print("Creating XML file " + args.xml)
cur_dir = os.path.dirname(os.path.realpath(__file__))
out = xmlout.XMLOutput(param_groups, args.board,
os.path.join(cur_dir, args.inject_xml))
out.Save(args.xml)
# Output to DokuWiki tables
if args.wiki or args.wiki_update:
out = dokuwikiout.DokuWikiTablesOutput(param_groups)
if args.wiki:
print("Creating wiki file " + args.wiki)
out.Save(args.wiki)
if args.wiki_update:
if args.wiki_user and args.wiki_pass:
print("Updating wiki page " + args.wiki_update)
xmlrpc = dokuwikirpc.get_xmlrpc(args.wiki_url, args.wiki_user, args.wiki_pass)
xmlrpc.wiki.putPage(args.wiki_update, out.output, {'sum': args.wiki_summary})
else:
print("Error: You need to specify DokuWiki XML-RPC username and password!")
# Output to Markdown/HTML tables
if args.markdown:
out = markdownout.MarkdownTablesOutput(param_groups)
if args.markdown:
print("Creating markdown file " + args.markdown)
out.Save(args.markdown)
#print("All done!")
if __name__ == "__main__":
main()