mirror of https://github.com/ArduPilot/ardupilot
Tools: param_meteadata: correct @Values{Plane} etc handling
This commit is contained in:
parent
19dfbb19e9
commit
eb2b1b3231
|
@ -246,20 +246,14 @@ def process_library(vehicle, library, pathprefix=None):
|
|||
global current_param
|
||||
current_param = p.name
|
||||
fields = prog_param_fields.findall(field_text)
|
||||
non_vehicle_specific_values_seen = False
|
||||
for field in fields:
|
||||
if field[0] in known_param_fields:
|
||||
value = re.sub('@PREFIX@', library.name, field[1])
|
||||
setattr(p, field[0], value)
|
||||
if field[0] == "Values":
|
||||
non_vehicle_specific_values_seen = True
|
||||
else:
|
||||
error("param: unknown parameter metadata field %s" % field[0])
|
||||
debug("matching %s" % field_text)
|
||||
fields = prog_param_tagged_fields.findall(field_text)
|
||||
this_vehicle_values_seen = False
|
||||
this_vehicle_value = None
|
||||
other_vehicle_values_seen = False
|
||||
for field in fields:
|
||||
only_for_vehicles = field[1].split(",")
|
||||
only_for_vehicles = [x.rstrip().lstrip() for x in only_for_vehicles]
|
||||
|
@ -268,25 +262,14 @@ def process_library(vehicle, library, pathprefix=None):
|
|||
error("Unknown vehicles (%s)" % delta)
|
||||
debug("field[0]=%s vehicle=%s field[1]=%s only_for_vehicles=%s\n" %
|
||||
(field[0], vehicle.name, field[1], str(only_for_vehicles)))
|
||||
if field[0] not in known_param_fields:
|
||||
error("tagged param: unknown parameter metadata field '%s'" % field[0])
|
||||
continue
|
||||
if vehicle.name not in only_for_vehicles:
|
||||
continue
|
||||
value = re.sub('@PREFIX@', library.name, field[2])
|
||||
if field[0] in ['Values', 'Bitmask']:
|
||||
if vehicle.name in only_for_vehicles:
|
||||
this_vehicle_values_seen = True
|
||||
this_vehicle_value = value
|
||||
if len(only_for_vehicles) > 1:
|
||||
other_vehicle_values_seen = True
|
||||
elif len(only_for_vehicles):
|
||||
other_vehicle_values_seen = True
|
||||
if field[0] in known_param_fields:
|
||||
setattr(p, field[0], value)
|
||||
else:
|
||||
error("tagged param<: unknown parameter metadata field '%s'" % field[0])
|
||||
if ((non_vehicle_specific_values_seen or not other_vehicle_values_seen) or this_vehicle_values_seen):
|
||||
if this_vehicle_values_seen and field[0] in ['Values', 'Bitmask']:
|
||||
setattr(p, field[0], this_vehicle_value)
|
||||
# debug("Appending (non_vehicle_specific_values_seen=%u "
|
||||
# "other_vehicle_values_seen=%u this_vehicle_values_seen=%u)" %
|
||||
# (non_vehicle_specific_values_seen, other_vehicle_values_seen, this_vehicle_values_seen))
|
||||
setattr(p, field[0], value)
|
||||
|
||||
p.path = path # Add path. Later deleted - only used for duplicates
|
||||
library.params.append(p)
|
||||
|
||||
|
|
Loading…
Reference in New Issue