ardupilot/Tools/autotest/param_metadata/param.py

123 lines
6.2 KiB
Python
Raw Normal View History

class Parameter(object):
def __init__(self, name, real_path):
self.name = name
self.real_path = real_path
class Vehicle(object):
def __init__(self, name, path, truename=None):
if truename is not None:
self.truename = truename
self.name = name
self.path = path
self.params = []
class Library(object):
def __init__(self, name):
self.name = name
self.params = []
known_param_fields = [
'Description',
'DisplayName',
'Values',
'Range',
'Units',
'Increment',
'User',
'RebootRequired',
2016-02-28 19:35:40 -04:00
'Bitmask',
'Volatile',
'ReadOnly',
'Calibration',
2012-07-04 21:42:38 -03:00
]
# 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' ,
'us' : 'microseconds' ,
'PWM' : 'PWM in microseconds' , # should be microseconds, this is NOT a SI unit, but follows https://github.com/ArduPilot/ardupilot/pull/5538#issuecomment-271943061
'Hz' : 'hertz' ,
'kHz' : 'kilohertz' ,
'1/s' : 'per second' , # Not SI but in some situations more user-friendly than hertz
# distance
'km' : 'kilometers' , # metre is the SI unit name, meter is the american spelling of it
'm' : 'meters' , # metre is the SI unit name, meter is the american spelling of it
'm/s' : 'meters per second' , # metre is the SI unit name, meter is the american spelling of it
'm/s/s' : 'meters per square second' , # metre is the SI unit name, meter is the american spelling of it
'm/s/s/s' : 'meters per cubic second' , # metre is the SI unit name, meter is the american spelling of it
'cm' : 'centimeters' , # metre is the SI unit name, meter is the american spelling of it
'cm/s' : 'centimeters per second' , # metre is the SI unit name, meter is the american spelling of it
'cm/s/s' : 'centimeters per square second', # metre is the SI unit name, meter is the american spelling of it
'cm/s/s/s': 'centimeters per cubic second' , # metre is the SI unit name, meter is the american spelling of it
'mm' : 'millimeters' , # metre is the SI unit name, meter is the american spelling of it
# temperature
'degC' : 'degrees Celsius' , # Not SI, but Kelvin is too cumbersome for most users
# angle
'deg' : 'degrees' , # Not SI, but is some situations more user-friendly than radians
'deg/s' : 'degrees per second' , # Not SI, but is some situations more user-friendly than radians
'deg/s/s' : 'degrees per square second', # Not SI, but is some situations more user-friendly than radians
'cdeg' : 'centidegrees' , # Not SI, but is some situations more user-friendly than radians
'cdeg/s' : 'centidegrees per second', # Not SI, but is some situations more user-friendly than radians
'cdeg/s/s': 'centidegrees per square second' , # Not SI, but is some situations more user-friendly than radians
'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' ,
'hPa' : 'hectopascal' ,
# ratio
'%' : 'percent' ,
'%/s' : 'percent per second' ,
'd%' : 'decipercent' , # decipercent is strange, but "per-mille" is even more exotic
2017-12-11 06:30:35 -04:00
'dB' : 'decibel' ,
# compound
2018-05-07 19:00:45 -03:00
'kB' : 'kilobytes' ,
2020-06-02 06:04:19 -03:00
'MB' : 'megabyte' ,
'm.m/s/s' : 'square meter per square second',
'deg/m/s' : 'degrees per meter per second' ,
'm/s/m' : 'meters per second per meter' , # Why not use Hz here ????
'mGauss/A': 'milligauss per ampere' ,
2018-05-25 19:47:27 -03:00
'mAh' : 'milliampere hour' ,
'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
2018-05-22 14:32:34 -03:00
'octal' : 'octal' ,
2019-08-29 20:58:17 -03:00
'RPM' : 'Revolutions Per Minute',
'kg/m/m' : 'kilograms per square meter', # metre is the SI unit name, meter is the american spelling of it
2020-11-09 20:54:43 -04:00
'kg/m.m' : 'kilogram per meter squared'
}
required_param_fields = [
'Description',
'DisplayName',
'User',
]
2012-07-04 21:42:38 -03:00
known_group_fields = [
'Path',
]