|
|
|
@ -71,7 +71,7 @@ for vehicle_path in vehicle_paths:
@@ -71,7 +71,7 @@ for vehicle_path in vehicle_paths:
|
|
|
|
|
vehicles.append(Vehicle(name, path, truename_map[name])) |
|
|
|
|
debug('Found vehicle type %s' % name) |
|
|
|
|
|
|
|
|
|
if len(vehicles) > 1: |
|
|
|
|
if len(vehicles) > 1 or len(vehicles) == 0: |
|
|
|
|
print("Single vehicle only, please") |
|
|
|
|
sys.exit(1) |
|
|
|
|
|
|
|
|
@ -166,6 +166,7 @@ def process_library(vehicle, library, pathprefix=None):
@@ -166,6 +166,7 @@ def process_library(vehicle, library, pathprefix=None):
|
|
|
|
|
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(",") |
|
|
|
@ -174,20 +175,25 @@ def process_library(vehicle, library, pathprefix=None):
@@ -174,20 +175,25 @@ def process_library(vehicle, library, pathprefix=None):
|
|
|
|
|
if len(delta): |
|
|
|
|
error("Unknown vehicles (%s)" % delta) |
|
|
|
|
debug("field[0]=%s vehicle=%s truename=%s field[1]=%s only_for_vehicles=%s\n" % (field[0], vehicle.name,vehicle.truename,field[1], str(only_for_vehicles))) |
|
|
|
|
value = re.sub('@PREFIX@', library.name, field[2]) |
|
|
|
|
if field[0] == "Values": |
|
|
|
|
if vehicle.truename 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: |
|
|
|
|
value = re.sub('@PREFIX@', library.name, field[2]) |
|
|
|
|
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: |
|
|
|
|
debug("Setting vehicle-specific value (%s)" % str(this_vehicle_value)) |
|
|
|
|
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)) |
|
|
|
|
library.params.append(p) |
|
|
|
|
|
|
|
|
|
group_matches = prog_groups.findall(p_text) |
|
|
|
|