mirror of https://github.com/ArduPilot/ardupilot
Tools: param_metadata: do not emit Legacy fields to rst/Wiki
This commit is contained in:
parent
792941d4de
commit
bbdbf33c21
|
@ -49,6 +49,9 @@ class EDNEmit(Emit):
|
|||
# remove any keys we don't really care to share
|
||||
for key in self.remove_keys:
|
||||
output_dict.pop(key, None)
|
||||
for key in list(output_dict.keys()):
|
||||
if not self.should_emit_field(param, key):
|
||||
output_dict.pop(key, None)
|
||||
|
||||
# rearrange bitmasks to be a vector with nil's if the bit doesn't have meaning
|
||||
if "bitmask" in output_dict:
|
||||
|
|
|
@ -19,3 +19,6 @@ class Emit:
|
|||
|
||||
def emit(self, g):
|
||||
pass
|
||||
|
||||
def should_emit_field(self, param, field):
|
||||
return field not in ['Legacy']
|
||||
|
|
|
@ -65,6 +65,8 @@ DO NOT EDIT
|
|||
t += "<ul>\n"
|
||||
|
||||
for field in param.__dict__.keys():
|
||||
if not self.should_emit_field(param, field):
|
||||
continue
|
||||
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]):
|
||||
values = (param.__dict__[field]).split(',')
|
||||
|
|
|
@ -56,6 +56,9 @@ class JSONEmit(Emit):
|
|||
name = name.split(':')[1]
|
||||
|
||||
# Remove various unwanted keys
|
||||
for key in list(param.__dict__.keys()):
|
||||
if not self.should_emit_field(param, key):
|
||||
param.__dict__.pop(key)
|
||||
for key in 'real_path', 'SortValues', '__field_text':
|
||||
try:
|
||||
param.__dict__.pop(key)
|
||||
|
|
|
@ -90,6 +90,8 @@ class MDEmit(Emit):
|
|||
t += "\n\n%s" % param.Description
|
||||
|
||||
for field in param.__dict__.keys():
|
||||
if not self.should_emit_field(param, field):
|
||||
continue
|
||||
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]):
|
||||
values = (param.__dict__[field]).split(',')
|
||||
|
|
|
@ -51,7 +51,8 @@ known_param_fields = [
|
|||
'ReadOnly',
|
||||
'Calibration',
|
||||
'Vector3Parameter',
|
||||
'SortValues'
|
||||
'SortValues',
|
||||
'Legacy',
|
||||
]
|
||||
|
||||
# Follow SI units conventions from:
|
||||
|
|
|
@ -225,6 +225,9 @@ This list is automatically generated from the latest ardupilot source code, and
|
|||
reference=reference)
|
||||
|
||||
for param in g.params:
|
||||
if getattr(param, "Legacy", False):
|
||||
# do not emit legacy parameters to the Wiki
|
||||
continue
|
||||
if not hasattr(param, 'DisplayName') or not hasattr(param, 'Description'):
|
||||
continue
|
||||
d = param.__dict__
|
||||
|
@ -263,6 +266,8 @@ This list is automatically generated from the latest ardupilot source code, and
|
|||
headings = []
|
||||
row = []
|
||||
for field in sorted(param.__dict__.keys()):
|
||||
if not self.should_emit_field(param, field):
|
||||
continue
|
||||
if (field not in ['name', 'DisplayName', 'Description', 'User', 'SortValues', 'RebootRequired'] and
|
||||
field in known_param_fields):
|
||||
headings.append(field)
|
||||
|
|
|
@ -63,6 +63,8 @@ class XmlEmit(Emit):
|
|||
|
||||
# Add values as chidren of this node
|
||||
for field in param.__dict__.keys():
|
||||
if not self.should_emit_field(param, field):
|
||||
continue
|
||||
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]):
|
||||
xml_values = etree.SubElement(xml_param, 'values')
|
||||
|
|
Loading…
Reference in New Issue