mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Tools: Follow SI units conventions
http://physics.nist.gov/cuu/Units/units.html http://physics.nist.gov/cuu/Units/outside.html and http://physics.nist.gov/cuu/Units/checklist.html http://www.bipm.org/en/publications/si-brochure/ http://www1.bipm.org/en/CGPM/db/3/2/ g_n unit for G-force one further constrain is that only printable (7bit) ASCII characters are allowed Add a validation so that Travis can validate the units Use full text unit information when generating .wiki, .rst and .html documentation Use both unit symbol and unit full text when generating .xml
This commit is contained in:
parent
5e938c8cc0
commit
d7c7deacdf
@ -3,7 +3,7 @@
|
||||
Emit docs in a form acceptable to the old Ardupilot wordpress docs site
|
||||
"""
|
||||
|
||||
from param import known_param_fields
|
||||
from param import known_param_fields, known_units
|
||||
from emit import Emit
|
||||
import cgi
|
||||
|
||||
@ -71,6 +71,11 @@ DO NOT EDIT
|
||||
v = value.split(':')
|
||||
t += "<tr><td>%s</td><td>%s</td></tr>\n" % (v[0], v[1])
|
||||
t += "</table>\n"
|
||||
elif field == 'Units':
|
||||
abreviated_units = param.__dict__[field]
|
||||
if abreviated_units != '':
|
||||
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))
|
||||
else:
|
||||
t += "<li>%s: %s</li>\n" % (field, cgi.escape(param.__dict__[field]))
|
||||
t += "</ul>\n"
|
||||
|
@ -30,6 +30,71 @@ known_param_fields = [
|
||||
'ReadOnly',
|
||||
]
|
||||
|
||||
# Follow SI units conventions from:
|
||||
# http://physics.nist.gov/cuu/Units/units.html
|
||||
# http://physics.nist.gov/cuu/Units/outside.html
|
||||
# and
|
||||
# http://physics.nist.gov/cuu/Units/checklist.html
|
||||
# http://www.bipm.org/en/publications/si-brochure/
|
||||
# http://www1.bipm.org/en/CGPM/db/3/2/ g_n unit for G-force
|
||||
# one further constrain is that only printable (7bit) ASCII characters are allowed
|
||||
known_units = {
|
||||
# abreviation : full-text (used in .html .rst and .wiki files)
|
||||
# time
|
||||
's' : 'seconds' ,
|
||||
'ds' : 'deciseconds' ,
|
||||
'cs' : 'centiseconds' ,
|
||||
'ms' : 'milliseconds' ,
|
||||
'PWM' : 'PWM in microseconds' , # should be microseconds, this is NOT a SI unit, but follows https://github.com/ArduPilot/ardupilot/pull/5538#issuecomment-271943061 and µs is not 7bit-ASCII
|
||||
'Hz' : 'hertz' ,
|
||||
# distance
|
||||
'km' : 'kilometers' , # metre is the SI unit name, _NOT_ meter
|
||||
'm' : 'meters' , # metre is the SI unit name, _NOT_ meter
|
||||
'm/s' : 'meters per second' , # metre is the SI unit name, _NOT_ meter
|
||||
'm/s/s' : 'meters per square second' , # metre is the SI unit name, _NOT_ meter
|
||||
'm/s/s/s' : 'meters per cubic second' , # metre is the SI unit name, _NOT_ meter
|
||||
'cm' : 'centimeters' , # metre is the SI unit name, _NOT_ meter
|
||||
'cm/s' : 'centimeters per second' , # metre is the SI unit name, _NOT_ meter
|
||||
'cm/s/s' : 'centimeters per square second', # metre is the SI unit name, _NOT_ meter
|
||||
'cm/s/s/s': 'centimeters per cubic second' , # metre is the SI unit name, _NOT_ meter
|
||||
'mm' : 'millimeters' , # metre is the SI unit name, _NOT_ meter
|
||||
# temperature
|
||||
'degC' : 'degrees Celsius' , # °C would be the correct abreviation, but it is not 7bit-ASCII
|
||||
# angle
|
||||
'deg' : 'degrees' , # ° would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'deg/s' : 'degrees per second' , # °/s would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'cdeg' : 'centidegrees' , # c° would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'cdeg/s' : 'centidegrees per second', # c°/s would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'cdeg/s/s': 'centidegrees per square second' ,
|
||||
'rad' : 'radians' ,
|
||||
'rad/s' : 'radians per second' ,
|
||||
'rad/s/s' : 'radians per square second' ,
|
||||
# electricity
|
||||
'A' : 'ampere' ,
|
||||
'V' : 'volt' ,
|
||||
'W' : 'watt' ,
|
||||
# magnetism
|
||||
'Gauss' : 'gauss' , # Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
|
||||
'Gauss/s' : 'gauss per second' , # Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
|
||||
'mGauss' : 'milligauss' , # Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
|
||||
# pressure
|
||||
'Pa' : 'pascal' ,
|
||||
'mbar' : 'millibar' ,
|
||||
# ratio
|
||||
'%' : 'percent' ,
|
||||
'%/s' : 'percent per second' ,
|
||||
'd%' : 'decipercent' , # ‰ would be the correct abreviation, but it is not 7bit-ASCII. decipercent is strange, but "per-mille" is even more exotic
|
||||
# compound
|
||||
'm.m/s/s' : 'square meter per square second', # m·m/s/s would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'deg/m/s' : 'degrees per meter per second' , # °/m/s would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'm/s/m' : 'meters per second per meter' , # Why not use Hz here ????
|
||||
'mGauss/A': 'milligauss per ampere' ,
|
||||
'mA.h' : 'milliampere hour' , # mA·h would be the correct abreviation, but it is not 7bit-ASCII
|
||||
'A/V' : 'ampere per volt' ,
|
||||
'm/V' : 'meters per volt' ,
|
||||
'gravities': 'standard acceleration due to gravity' , # g_n would be a more correct unit, but IMHO no one understands what g_n means
|
||||
}
|
||||
|
||||
required_param_fields = [
|
||||
'Description',
|
||||
'DisplayName',
|
||||
|
@ -7,7 +7,7 @@ import sys
|
||||
from optparse import OptionParser
|
||||
|
||||
from param import (Library, Parameter, Vehicle, known_group_fields,
|
||||
known_param_fields, required_param_fields)
|
||||
known_param_fields, required_param_fields, known_units)
|
||||
from htmlemit import HtmlEmit
|
||||
from rstemit import RSTEmit
|
||||
from wikiemit import WikiEmit
|
||||
@ -203,6 +203,10 @@ def validate(param):
|
||||
if not is_number(max_value):
|
||||
error("Max value not number: %s %s" % (param.name, max_value))
|
||||
return
|
||||
# Validate units
|
||||
if (hasattr(param, "Units")):
|
||||
if (param.__dict__["Units"] != "") and (param.__dict__["Units"] not in known_units):
|
||||
error("unknown units field '%s'" % param.__dict__["Units"])
|
||||
|
||||
for vehicle in vehicles:
|
||||
for param in vehicle.params:
|
||||
|
@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python
|
||||
from __future__ import print_function
|
||||
import re
|
||||
from param import known_param_fields
|
||||
from param import known_param_fields, known_units
|
||||
from emit import Emit
|
||||
import cgi
|
||||
|
||||
@ -241,6 +241,11 @@ Complete Parameter List
|
||||
elif field == "Range":
|
||||
(param_min, param_max) = (param.__dict__[field]).split(' ')
|
||||
row.append("%s - %s" % (param_min, param_max,))
|
||||
elif field == 'Units':
|
||||
abreviated_units = param.__dict__[field]
|
||||
if abreviated_units != '':
|
||||
units = known_units[abreviated_units] # use the known_units dictionary to convert the abreviated unit into a full textual one
|
||||
row.append(cgi.escape(units))
|
||||
else:
|
||||
row.append(cgi.escape(param.__dict__[field]))
|
||||
if len(row):
|
||||
|
@ -3,7 +3,7 @@
|
||||
import re
|
||||
|
||||
from emit import Emit
|
||||
from param import known_param_fields
|
||||
from param import known_param_fields, known_units
|
||||
|
||||
|
||||
# Emit docs in a form acceptable to the APM wiki site
|
||||
@ -63,6 +63,11 @@ class WikiEmit(Emit):
|
||||
for value in values:
|
||||
v = value.split(':')
|
||||
t += "|| " + v[0] + " || " + self.camelcase_escape(v[1]) + " ||\n"
|
||||
elif field == 'Units':
|
||||
abreviated_units = param.__dict__[field]
|
||||
if abreviated_units != '':
|
||||
units = known_units[abreviated_units] # use the known_units dictionary to convert the abreviated unit into a full textual one
|
||||
t += " * %s: %s\n" % (self.camelcase_escape(field), self.wikichars_escape(units))
|
||||
else:
|
||||
t += " * %s: %s\n" % (self.camelcase_escape(field), self.wikichars_escape(param.__dict__[field]))
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
from xml.sax.saxutils import escape, quoteattr
|
||||
|
||||
from emit import Emit
|
||||
from param import known_param_fields
|
||||
from param import known_param_fields, known_units
|
||||
|
||||
|
||||
# Emit APM documentation in an machine readable XML format
|
||||
@ -60,6 +60,12 @@ class XmlEmit(Emit):
|
||||
t += '''<value code=%s>%s</value>\n''' % (quoteattr(v[0]), escape(v[1])) # i.e. numeric value, string label
|
||||
|
||||
t += "</values>\n"
|
||||
elif field == 'Units':
|
||||
abreviated_units = param.__dict__[field]
|
||||
if abreviated_units != '':
|
||||
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 += '''<field name=%s>%s</field>\n''' % (quoteattr('UnitText'), escape(units)) # i.e. ampere per second
|
||||
else:
|
||||
t += '''<field name=%s>%s</field>\n''' % (quoteattr(field), escape(param.__dict__[field])) # i.e. Range: 0 10
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user