mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Tools: build all vehicles in build-with-disabled-features
This commit is contained in:
parent
6ab96fe8a9
commit
4847a61868
@ -34,22 +34,13 @@ from pysim import util
|
||||
|
||||
class Builder():
|
||||
|
||||
def __init__(self):
|
||||
self.config = 'ArduCopter/APM_Config.h'
|
||||
self.autotest_build = "build.ArduCopter"
|
||||
def __init__(self, spec):
|
||||
self.config = spec["config"]
|
||||
self.autotest_build = spec["builddir"]
|
||||
|
||||
# list other features that have to be disabled when a feature
|
||||
# is disabled (recursion not done; be exhaustive):
|
||||
self.reverse_deps = {
|
||||
"AC_FENCE": ["AC_AVOID_ENABLED"],
|
||||
"PROXIMITY_ENABLED": ["AC_AVOID_ENABLED"],
|
||||
"AC_RALLY": ["AC_TERRAIN"],
|
||||
"MODE_AUTO_ENABLED": ["AC_TERRAIN", "MODE_GUIDED"],
|
||||
"MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
"BEACON_ENABLED": ["AC_AVOID_ENABLED"],
|
||||
"MODE_CIRCLE_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
"MODE_GUIDED_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
}
|
||||
self.reverse_deps = spec["reverse-deps"]
|
||||
|
||||
def reverse_deps_for_var(self, var):
|
||||
return self.reverse_deps.get(var, [])
|
||||
@ -59,29 +50,56 @@ class Builder():
|
||||
|
||||
def get_config_variables(self):
|
||||
ret = []
|
||||
r = (' *# *define +([A-Z_]+)\s+'
|
||||
'(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)')
|
||||
with open(util.reltopdir(self.config)) as fd:
|
||||
for line in fd:
|
||||
match = re.match('//#define ([A-Z_]+)\s+(ENABLED|DISABLED)',
|
||||
line)
|
||||
if match is not None:
|
||||
ret.append(match.group(1))
|
||||
return ret
|
||||
match = re.match(r, line)
|
||||
if match is None:
|
||||
continue
|
||||
if match.group(1) in ("ENABLE", "DISABLE",
|
||||
"!HAL_MINIMIZE_FEATURES"):
|
||||
continue
|
||||
ret.append( (match.group(1), match.group(2) ))
|
||||
return set(ret)
|
||||
|
||||
def disable_option_in_config(self, var):
|
||||
tmpfile = util.reltopdir(self.config) + ".tmp"
|
||||
shutil.move(self.config, tmpfile)
|
||||
out_fd = open(self.config, 'w+')
|
||||
with open(util.reltopdir(tmpfile)) as fd:
|
||||
for line in fd:
|
||||
things_to_toggle = self.reverse_deps_for_var(var)
|
||||
things_to_toggle.append(var)
|
||||
for thing in things_to_toggle:
|
||||
line = re.sub(
|
||||
'//(#define\s+%s\s+(ENABLED|DISABLED))' % thing,
|
||||
"\\1",
|
||||
line)
|
||||
out_fd.write(line)
|
||||
out_fd.close()
|
||||
with open(self.config, 'w+') as out_fd:
|
||||
with open(util.reltopdir(tmpfile)) as fd:
|
||||
did_enable = False
|
||||
for line in fd:
|
||||
regex = ' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % (var[0],)
|
||||
match = re.match(regex, line)
|
||||
if match is not None:
|
||||
if (match.group(1) in ["ENABLED",
|
||||
"!HAL_MINIMIZE_FEATURES"]):
|
||||
fnoo = "DISABLED"
|
||||
else:
|
||||
fnoo = "ENABLED"
|
||||
did_enable = True
|
||||
|
||||
line = "#define %s %s\n" % (var[0], fnoo)
|
||||
out_fd.write(line)
|
||||
# turn dependencies on or off:
|
||||
tmpfile = util.reltopdir(self.config) + ".tmp-deps"
|
||||
shutil.move(self.config, tmpfile)
|
||||
with open(self.config, 'w+') as out_fd:
|
||||
with open(util.reltopdir(tmpfile)) as fd:
|
||||
for line in fd:
|
||||
things_to_toggle = self.reverse_deps_for_var(var[0])
|
||||
for thing in things_to_toggle:
|
||||
regex = ' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % thing
|
||||
match = re.match(regex, line)
|
||||
if match is not None:
|
||||
if did_enable:
|
||||
fnoo = "ENABLED"
|
||||
else:
|
||||
fnoo = "DISABLED"
|
||||
|
||||
line = "#define %s %s\n" % (thing, fnoo)
|
||||
out_fd.write(line)
|
||||
|
||||
def backup_config_filepath(self):
|
||||
return util.reltopdir(self.config) + ".backup"
|
||||
@ -102,22 +120,92 @@ class Builder():
|
||||
return ret == 0
|
||||
|
||||
def run(self):
|
||||
self.progress("Doing: %s" % (self.autotest_build,))
|
||||
self.backup_config()
|
||||
successes = []
|
||||
failures = []
|
||||
for var in self.get_config_variables():
|
||||
print("var: %s" % str(var))
|
||||
self.disable_option_in_config(var)
|
||||
if self.build_works():
|
||||
self.progress("%s OK" % var)
|
||||
successes.append(var)
|
||||
self.progress("%s OK" % var[0])
|
||||
successes.append(var[0])
|
||||
else:
|
||||
self.progress("%s BAD" % var)
|
||||
failures.append(var)
|
||||
self.progress("%s BAD" % var[0])
|
||||
failures.append(var[0])
|
||||
self.restore_config()
|
||||
|
||||
self.successes = successes
|
||||
self.failures = failures
|
||||
|
||||
self.progress("Successes: %s" % str(successes))
|
||||
self.progress("Failures: %s" % str(failures))
|
||||
|
||||
class BuilderCopter(Builder):
|
||||
def get_config_variables(self):
|
||||
ret = []
|
||||
r = '//#define ([A-Z_]+)\s+(ENABLED|DISABLED!HAL_MINIMIZE_FEATURES)'
|
||||
with open(util.reltopdir(self.config)) as fd:
|
||||
for line in fd:
|
||||
print("line: %s" % line)
|
||||
match = re.match(r, line)
|
||||
if match is not None:
|
||||
ret.append(match.group(1))
|
||||
return ret
|
||||
|
||||
builder = Builder()
|
||||
builder.run()
|
||||
|
||||
# read reverse dep "MODE_AUTO_ENABLED": ["AC_TERRAIN", "MODE_GUIDED"] thusly:
|
||||
# "if mode-auto is disabled then you must also disable terrain and guided mode"
|
||||
|
||||
specs = [
|
||||
{
|
||||
"config": 'ArduCopter/config.h',
|
||||
"builddir": "build.ArduCopter",
|
||||
"reverse-deps": {
|
||||
"AC_FENCE": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
||||
"PROXIMITY_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED" ],
|
||||
"AC_RALLY": ["AC_TERRAIN"],
|
||||
"MODE_AUTO_ENABLED": ["AC_TERRAIN", "MODE_GUIDED"],
|
||||
"MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
"BEACON_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
||||
"MODE_CIRCLE_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
"MODE_GUIDED_ENABLED": ["MODE_AUTO_ENABLED", "AC_TERRAIN"],
|
||||
"AC_AVOID_ENABLED": ["MODE_FOLLOW_ENABLED"],
|
||||
},
|
||||
}, {
|
||||
"config": 'ArduPlane/config.h',
|
||||
"builddir": "build.ArduPlane",
|
||||
"reverse-deps": {
|
||||
},
|
||||
}, {
|
||||
"config": 'APMrover2/config.h',
|
||||
"builddir": "build.APMrover2",
|
||||
"reverse-deps": {
|
||||
},
|
||||
}, {
|
||||
"config": 'ArduSub/config.h',
|
||||
"builddir": "build.ArduSub",
|
||||
"reverse-deps": {
|
||||
"AC_FENCE": ["AVOIDANCE_ENABLED"],
|
||||
"PROXIMITY_ENABLED": ["AVOIDANCE_ENABLED"],
|
||||
"AC_RALLY": ["AC_TERRAIN"],
|
||||
},
|
||||
}, {
|
||||
"config": 'AntennaTracker/config.h',
|
||||
"builddir": "build.AntennaTracker",
|
||||
"reverse-deps": {
|
||||
},
|
||||
},
|
||||
]
|
||||
|
||||
builders = []
|
||||
for spec in specs:
|
||||
builder = Builder(spec)
|
||||
builder.run()
|
||||
builders.append(builder)
|
||||
|
||||
print("")
|
||||
for builder in builders:
|
||||
print("Builder: %s" % builder.autotest_build)
|
||||
print(" Successes: %s" % builder.successes)
|
||||
print(" Failures: %s" % builder.failures)
|
||||
|
Loading…
Reference in New Issue
Block a user