mirror of https://github.com/ArduPilot/ardupilot
Tools: param_metadata: remove more multi-vehicle support
This script hasn't supported emitting multiple vehicles for a very long time, but this was enforced using a check and we kept a list of vehicles around for no very good reason.
This commit is contained in:
parent
0f4d1cec54
commit
97e57932c4
|
@ -55,7 +55,6 @@ apm_tools_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../.
|
||||||
vehicle_paths += glob.glob(apm_tools_path + "%s/Parameters.cpp" % args.vehicle)
|
vehicle_paths += glob.glob(apm_tools_path + "%s/Parameters.cpp" % args.vehicle)
|
||||||
vehicle_paths.sort(reverse=True)
|
vehicle_paths.sort(reverse=True)
|
||||||
|
|
||||||
vehicles = []
|
|
||||||
libraries = []
|
libraries = []
|
||||||
|
|
||||||
# AP_Vehicle also has parameters rooted at "", but isn't referenced
|
# AP_Vehicle also has parameters rooted at "", but isn't referenced
|
||||||
|
@ -96,17 +95,18 @@ truename_map = {
|
||||||
}
|
}
|
||||||
valid_truenames = frozenset(truename_map.values())
|
valid_truenames = frozenset(truename_map.values())
|
||||||
|
|
||||||
for vehicle_path in vehicle_paths:
|
if len(vehicle_paths) > 1 or len(vehicle_paths) == 0:
|
||||||
name = os.path.basename(os.path.dirname(vehicle_path))
|
|
||||||
path = os.path.normpath(os.path.dirname(vehicle_path))
|
|
||||||
vehicles.append(Vehicle(name, path, truename_map[name]))
|
|
||||||
debug('Found vehicle type %s' % name)
|
|
||||||
|
|
||||||
if len(vehicles) > 1 or len(vehicles) == 0:
|
|
||||||
print("Single vehicle only, please")
|
print("Single vehicle only, please")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
for vehicle in vehicles:
|
vehicle_path = vehicle_paths[0]
|
||||||
|
|
||||||
|
name = os.path.basename(os.path.dirname(vehicle_path))
|
||||||
|
path = os.path.normpath(os.path.dirname(vehicle_path))
|
||||||
|
vehicle = Vehicle(name, path, truename_map[name])
|
||||||
|
debug('Found vehicle type %s' % vehicle.name)
|
||||||
|
|
||||||
|
def process_vehicle(vehicle):
|
||||||
debug("===\n\n\nProcessing %s" % vehicle.name)
|
debug("===\n\n\nProcessing %s" % vehicle.name)
|
||||||
current_file = vehicle.path+'/Parameters.cpp'
|
current_file = vehicle.path+'/Parameters.cpp'
|
||||||
|
|
||||||
|
@ -163,6 +163,8 @@ for vehicle in vehicles:
|
||||||
current_file = None
|
current_file = None
|
||||||
debug("Processed %u params" % len(vehicle.params))
|
debug("Processed %u params" % len(vehicle.params))
|
||||||
|
|
||||||
|
process_vehicle(vehicle)
|
||||||
|
|
||||||
debug("Found %u documented libraries" % len(libraries))
|
debug("Found %u documented libraries" % len(libraries))
|
||||||
|
|
||||||
if args.emit_sitl:
|
if args.emit_sitl:
|
||||||
|
@ -174,8 +176,6 @@ libraries = list(libraries)
|
||||||
|
|
||||||
alllibs = libraries[:]
|
alllibs = libraries[:]
|
||||||
|
|
||||||
vehicle = vehicles[0]
|
|
||||||
|
|
||||||
def process_library(vehicle, library, pathprefix=None):
|
def process_library(vehicle, library, pathprefix=None):
|
||||||
'''process one library'''
|
'''process one library'''
|
||||||
paths = library.Path.split(',')
|
paths = library.Path.split(',')
|
||||||
|
@ -187,10 +187,7 @@ def process_library(vehicle, library, pathprefix=None):
|
||||||
if pathprefix is not None:
|
if pathprefix is not None:
|
||||||
libraryfname = os.path.join(pathprefix, path)
|
libraryfname = os.path.join(pathprefix, path)
|
||||||
elif path.find('/') == -1:
|
elif path.find('/') == -1:
|
||||||
if len(vehicles) != 1:
|
libraryfname = os.path.join(vehicle.path, path)
|
||||||
print("Unable to handle multiple vehicles with .pde library")
|
|
||||||
continue
|
|
||||||
libraryfname = os.path.join(vehicles[0].path, path)
|
|
||||||
else:
|
else:
|
||||||
libraryfname = os.path.normpath(os.path.join(apm_path + '/libraries/' + path))
|
libraryfname = os.path.normpath(os.path.join(apm_path + '/libraries/' + path))
|
||||||
if path and os.path.exists(libraryfname):
|
if path and os.path.exists(libraryfname):
|
||||||
|
@ -381,12 +378,10 @@ def validate(param):
|
||||||
if not param.Description or not param.Description.strip():
|
if not param.Description or not param.Description.strip():
|
||||||
error("Empty Description (%s)" % param)
|
error("Empty Description (%s)" % param)
|
||||||
|
|
||||||
for vehicle in vehicles:
|
for param in vehicle.params:
|
||||||
for param in vehicle.params:
|
|
||||||
clean_param(param)
|
clean_param(param)
|
||||||
|
|
||||||
for vehicle in vehicles:
|
for param in vehicle.params:
|
||||||
for param in vehicle.params:
|
|
||||||
validate(param)
|
validate(param)
|
||||||
|
|
||||||
# Find duplicate names in library and fix up path
|
# Find duplicate names in library and fix up path
|
||||||
|
@ -452,7 +447,6 @@ for emitter_name in emitters_to_use:
|
||||||
emit = all_emitters[emitter_name](sitl=args.emit_sitl)
|
emit = all_emitters[emitter_name](sitl=args.emit_sitl)
|
||||||
|
|
||||||
if not args.emit_sitl:
|
if not args.emit_sitl:
|
||||||
for vehicle in vehicles:
|
|
||||||
emit.emit(vehicle)
|
emit.emit(vehicle)
|
||||||
|
|
||||||
emit.start_libraries()
|
emit.start_libraries()
|
||||||
|
|
Loading…
Reference in New Issue