mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 22:58:10 +08:00
parameters: fix JSON output types
All types were previously output as strings
This commit is contained in:
@@ -25,11 +25,15 @@ class JsonOutput():
|
||||
"short_desc": "shortDesc",
|
||||
"long_desc": "longDesc",
|
||||
"unit": "units",
|
||||
"decimal": "decimalPlaces",
|
||||
}
|
||||
schema_map_typed = {
|
||||
"min": "min",
|
||||
"max": "max",
|
||||
"increment": "increment",
|
||||
"reboot_required": "rebootRequired"
|
||||
}
|
||||
schema_map_fix_type = {
|
||||
"reboot_required": ("rebootRequired", bool),
|
||||
"decimal": ("decimalPlaces", int),
|
||||
}
|
||||
allowed_types = { "Uint8", "Int8", "Uint16", "Int16", "Uint32", "Int32", "Float"}
|
||||
|
||||
@@ -38,22 +42,28 @@ class JsonOutput():
|
||||
for group in groups:
|
||||
group_name=group.GetName()
|
||||
|
||||
def get_typed_value(value: str, type_name: str):
|
||||
if type_name == 'Float': return float(value)
|
||||
if type_name == 'Int32': return int(value)
|
||||
return value
|
||||
|
||||
for param in group.GetParams():
|
||||
if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName():
|
||||
curr_param=dict()
|
||||
curr_param['name'] = param.GetName()
|
||||
curr_param['default'] = param.GetDefault()
|
||||
curr_param['type'] = param.GetType().capitalize()
|
||||
if not curr_param['type'] in allowed_types:
|
||||
type_name = param.GetType().capitalize()
|
||||
curr_param['type'] = type_name
|
||||
if not type_name in allowed_types:
|
||||
print("Error: %s type not supported: curr_param['type']" % (curr_param['name'],curr_param['type']) )
|
||||
sys.Exit(1)
|
||||
curr_param['default'] = get_typed_value(param.GetDefault(), type_name)
|
||||
|
||||
curr_param['group'] = group_name
|
||||
if (param.GetCategory()):
|
||||
if param.GetCategory():
|
||||
curr_param['category'] = param.GetCategory()
|
||||
|
||||
if param.GetVolatile():
|
||||
curr_param['volatile'] = "True"
|
||||
curr_param['volatile'] = True
|
||||
|
||||
last_param_name = param.GetName()
|
||||
for code in param.GetFieldCodes():
|
||||
@@ -67,11 +77,15 @@ class JsonOutput():
|
||||
continue
|
||||
else:
|
||||
#map PX4 param field names to schema names
|
||||
if code in schema_map:
|
||||
curr_param[schema_map[code]] = value
|
||||
else:
|
||||
print('ERROR: Field not in json schema: %s' % code)
|
||||
sys.exit(1)
|
||||
if code in schema_map:
|
||||
curr_param[schema_map[code]] = value
|
||||
elif code in schema_map_typed:
|
||||
curr_param[schema_map_typed[code]] = get_typed_value(value, type_name)
|
||||
elif code in schema_map_fix_type:
|
||||
curr_param[schema_map_fix_type[code][0]] = schema_map_fix_type[code][1](value)
|
||||
else:
|
||||
print('ERROR: Field not in json schema: %s' % code)
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
if last_param_name != param.GetName():
|
||||
@@ -83,7 +97,7 @@ class JsonOutput():
|
||||
codes_list=list()
|
||||
for item in enum_codes:
|
||||
code_dict=dict()
|
||||
code_dict['value']=item
|
||||
code_dict['value']=get_typed_value(item, type_name)
|
||||
code_dict['description']=param.GetEnumValue(item)
|
||||
codes_list.append(code_dict)
|
||||
curr_param['values'] = codes_list
|
||||
@@ -93,7 +107,7 @@ class JsonOutput():
|
||||
bitmasks_list=list()
|
||||
for index in param.GetBitmaskList():
|
||||
bitmask_dict=dict()
|
||||
bitmask_dict['index']=index
|
||||
bitmask_dict['index']=int(index)
|
||||
bitmask_dict['description']=param.GetBitmaskBit(index)
|
||||
bitmasks_list.append(bitmask_dict)
|
||||
curr_param['bitmask'] = bitmasks_list
|
||||
|
||||
@@ -162,11 +162,11 @@ class Parameter(object):
|
||||
"""
|
||||
Return value of the given bitmask code or None if not found.
|
||||
"""
|
||||
fv = self.bitmask.get(index)
|
||||
fv = self.bitmask.get(index)
|
||||
if not fv:
|
||||
# required because python 3 sorted does not accept None
|
||||
return ""
|
||||
return fv
|
||||
return fv.strip()
|
||||
|
||||
class SourceParser(object):
|
||||
"""
|
||||
|
||||
Reference in New Issue
Block a user