2018-02-20 21:13:49 -04:00
|
|
|
#!/usr/bin/env python
|
|
|
|
|
|
|
|
from __future__ import print_function
|
|
|
|
|
|
|
|
'''
|
|
|
|
Build ArduPilot with various build-time options enabled or disabled
|
2018-02-21 18:47:54 -04:00
|
|
|
|
|
|
|
Usage is straight forward; invoke this script from the root directory
|
|
|
|
of an ArduPilot checkout:
|
|
|
|
|
2019-08-30 07:42:37 -03:00
|
|
|
pbarker@bluebottle:~/rc/ardupilot(build-with-disabled-features)$ ./Tools/autotest/build-with-disabled-features.py
|
2018-02-21 18:47:54 -04:00
|
|
|
|
|
|
|
BWFD: Building
|
|
|
|
Running: ("/home/pbarker/rc/ardupilot/Tools/autotest/autotest.py" "build.ArduCopter") in (.)
|
|
|
|
lckfile='/home/pbarker/rc/buildlogs/autotest.lck'
|
|
|
|
.
|
|
|
|
.
|
|
|
|
.
|
|
|
|
>>>> PASSED STEP: build.ArduCopter at Thu Feb 22 09:46:43 2018
|
|
|
|
check step: build.ArduCopter
|
|
|
|
BWFD: ADVANCED_FAILSAFE OK
|
2022-07-19 08:33:13 -03:00
|
|
|
BWFD: Successes: ['MOUNT', 'AUTOTUNE_ENABLED', 'AP_FENCE_ENABLED', 'CAMERA', 'RANGEFINDER_ENABLED', 'PROXIMITY_ENABLED', 'AC_RALLY', 'AC_AVOID_ENABLED', 'PARACHUTE', 'NAV_GUIDED', 'OPTFLOW', 'VISUAL_ODOMETRY_ENABLED', 'ADSB_ENABLED', 'PRECISION_LANDING', 'SPRAYER', 'WINCH_ENABLED', 'ADVANCED_FAILSAFE']
|
2018-02-21 18:47:54 -04:00
|
|
|
BWFD: Failures: ['LOGGING_ENABLED']
|
|
|
|
pbarker@bluebottle:~/rc/ardupilot(build-with-disabled-features)$ q
|
|
|
|
|
2022-01-09 20:06:29 -04:00
|
|
|
AP_FLAKE8_CLEAN
|
|
|
|
|
2019-08-30 07:42:37 -03:00
|
|
|
''' # noqa
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
import re
|
|
|
|
import shutil
|
|
|
|
import subprocess
|
2019-08-29 01:06:00 -03:00
|
|
|
import sys
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
from pysim import util
|
|
|
|
|
|
|
|
|
|
|
|
class Builder():
|
|
|
|
|
2019-08-29 01:06:00 -03:00
|
|
|
def __init__(self, spec, autotest=False, board=None):
|
2018-04-20 01:09:03 -03:00
|
|
|
self.config = spec["config"]
|
2019-08-29 01:06:00 -03:00
|
|
|
self.autotest_build = spec["autotest_target"]
|
|
|
|
self.target_binary = spec["target_binary"]
|
2019-11-01 02:49:25 -03:00
|
|
|
if "blacklist_options" in spec:
|
|
|
|
self.blacklist_options = spec["blacklist_options"]
|
|
|
|
else:
|
|
|
|
self.blacklist_options = []
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
# list other features that have to be disabled when a feature
|
|
|
|
# is disabled (recursion not done; be exhaustive):
|
2018-04-20 01:09:03 -03:00
|
|
|
self.reverse_deps = spec["reverse-deps"]
|
2019-08-29 01:06:00 -03:00
|
|
|
self.autotest = autotest
|
|
|
|
self.board = board
|
|
|
|
|
|
|
|
def description(self):
|
|
|
|
if self.autotest:
|
|
|
|
return self.autotest_build
|
|
|
|
if self.target_binary:
|
|
|
|
return "%s:%s" % (self.board, self.target_binary)
|
|
|
|
print("Bad config")
|
|
|
|
sys.exit(1)
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
def reverse_deps_for_var(self, var):
|
|
|
|
return self.reverse_deps.get(var, [])
|
|
|
|
|
|
|
|
def progress(self, string):
|
|
|
|
print("BWFD: %s" % string)
|
|
|
|
|
|
|
|
def get_config_variables(self):
|
|
|
|
ret = []
|
2022-01-09 20:06:29 -04:00
|
|
|
r = (r' *# *define +([A-Z_]+)\s+'
|
2018-04-20 01:09:03 -03:00
|
|
|
'(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)')
|
2018-02-20 21:13:49 -04:00
|
|
|
with open(util.reltopdir(self.config)) as fd:
|
|
|
|
for line in fd:
|
2018-04-20 01:09:03 -03:00
|
|
|
match = re.match(r, line)
|
|
|
|
if match is None:
|
|
|
|
continue
|
|
|
|
if match.group(1) in ("ENABLE", "DISABLE",
|
|
|
|
"!HAL_MINIMIZE_FEATURES"):
|
|
|
|
continue
|
2019-11-01 02:49:25 -03:00
|
|
|
if match.group(1) in self.blacklist_options:
|
|
|
|
print("Skipping (%s)" % match.group(1))
|
|
|
|
continue
|
2019-08-30 07:42:37 -03:00
|
|
|
ret.append((match.group(1), match.group(2)))
|
2018-04-20 01:09:03 -03:00
|
|
|
return set(ret)
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
def disable_option_in_config(self, var):
|
|
|
|
tmpfile = util.reltopdir(self.config) + ".tmp"
|
|
|
|
shutil.move(self.config, tmpfile)
|
2018-04-20 01:09:03 -03:00
|
|
|
with open(self.config, 'w+') as out_fd:
|
|
|
|
with open(util.reltopdir(tmpfile)) as fd:
|
|
|
|
did_enable = False
|
|
|
|
for line in fd:
|
2022-01-09 20:06:29 -04:00
|
|
|
regex = r' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % (var[0],)
|
2018-04-20 01:09:03 -03:00
|
|
|
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
|
2019-08-30 07:42:37 -03:00
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
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:
|
2022-01-09 20:06:29 -04:00
|
|
|
regex = r' *# *define +%s\s+(ENABLED|DISABLED|!HAL_MINIMIZE_FEATURES)' % thing
|
2018-04-20 01:09:03 -03:00
|
|
|
match = re.match(regex, line)
|
|
|
|
if match is not None:
|
|
|
|
if did_enable:
|
|
|
|
fnoo = "ENABLED"
|
|
|
|
else:
|
|
|
|
fnoo = "DISABLED"
|
2019-08-30 07:42:37 -03:00
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
line = "#define %s %s\n" % (thing, fnoo)
|
|
|
|
out_fd.write(line)
|
2018-02-20 21:13:49 -04:00
|
|
|
|
|
|
|
def backup_config_filepath(self):
|
|
|
|
return util.reltopdir(self.config) + ".backup"
|
|
|
|
|
|
|
|
def backup_config(self):
|
|
|
|
shutil.copy(self.config, self.backup_config_filepath())
|
|
|
|
|
|
|
|
def restore_config(self):
|
|
|
|
shutil.copy(self.backup_config_filepath(), self.config)
|
|
|
|
|
|
|
|
def build_works(self):
|
|
|
|
self.progress("Building")
|
2019-08-29 01:06:00 -03:00
|
|
|
|
|
|
|
if self.autotest:
|
|
|
|
return self.build_works_autotest()
|
|
|
|
|
|
|
|
try:
|
|
|
|
ret = util.run_cmd(["./waf", "configure", "--board", self.board])
|
|
|
|
except subprocess.CalledProcessError:
|
|
|
|
return False
|
|
|
|
if ret != 0:
|
|
|
|
return False
|
|
|
|
try:
|
|
|
|
ret = util.run_cmd(["./waf", "build", "--target", self.target_binary])
|
|
|
|
except subprocess.CalledProcessError:
|
|
|
|
return False
|
|
|
|
if ret != 0:
|
|
|
|
return False
|
|
|
|
|
|
|
|
return True
|
|
|
|
|
|
|
|
def build_works_autotest(self):
|
2018-02-20 21:13:49 -04:00
|
|
|
autotest = util.reltopdir("Tools/autotest/autotest.py")
|
|
|
|
try:
|
|
|
|
ret = util.run_cmd([autotest, self.autotest_build])
|
|
|
|
except subprocess.CalledProcessError:
|
|
|
|
return False
|
|
|
|
return ret == 0
|
|
|
|
|
|
|
|
def run(self):
|
2018-04-20 01:09:03 -03:00
|
|
|
self.progress("Doing: %s" % (self.autotest_build,))
|
2018-02-20 21:13:49 -04:00
|
|
|
self.backup_config()
|
|
|
|
successes = []
|
|
|
|
failures = []
|
|
|
|
for var in self.get_config_variables():
|
2018-04-20 01:09:03 -03:00
|
|
|
print("var: %s" % str(var))
|
2018-02-20 21:13:49 -04:00
|
|
|
self.disable_option_in_config(var)
|
|
|
|
if self.build_works():
|
2018-04-20 01:09:03 -03:00
|
|
|
self.progress("%s OK" % var[0])
|
|
|
|
successes.append(var[0])
|
2018-02-20 21:13:49 -04:00
|
|
|
else:
|
2018-04-20 01:09:03 -03:00
|
|
|
self.progress("%s BAD" % var[0])
|
|
|
|
failures.append(var[0])
|
2018-02-20 21:13:49 -04:00
|
|
|
self.restore_config()
|
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
self.successes = successes
|
|
|
|
self.failures = failures
|
|
|
|
|
2018-02-20 21:13:49 -04:00
|
|
|
self.progress("Successes: %s" % str(successes))
|
|
|
|
self.progress("Failures: %s" % str(failures))
|
|
|
|
|
2019-08-30 07:42:37 -03:00
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
class BuilderCopter(Builder):
|
|
|
|
def get_config_variables(self):
|
|
|
|
ret = []
|
2022-01-09 20:06:29 -04:00
|
|
|
r = r'//#define ([A-Z_]+)\s+(ENABLED|DISABLED!HAL_MINIMIZE_FEATURES)'
|
2018-04-20 01:09:03 -03:00
|
|
|
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
|
|
|
|
|
|
|
|
|
2021-02-12 23:40:10 -04:00
|
|
|
# read reverse dep "MODE_AUTO_ENABLED": ["MODE_GUIDED"] thusly:
|
|
|
|
# "if mode-auto is disabled then you must also disable guided mode"
|
2018-02-20 21:13:49 -04:00
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
specs = [
|
|
|
|
{
|
|
|
|
"config": 'ArduCopter/config.h',
|
2020-03-26 23:46:12 -03:00
|
|
|
"autotest_target": "build.Copter",
|
2019-08-29 01:06:00 -03:00
|
|
|
"target_binary": "bin/arducopter",
|
2018-04-20 01:09:03 -03:00
|
|
|
"reverse-deps": {
|
2022-07-19 08:33:13 -03:00
|
|
|
"AP_FENCE_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2019-08-30 07:42:37 -03:00
|
|
|
"PROXIMITY_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2021-02-12 23:40:10 -04:00
|
|
|
"MODE_AUTO_ENABLED": ["MODE_GUIDED", "ADVANCED_FAILSAFE"],
|
|
|
|
"MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "MODE_SMARTRTL_ENABLED"],
|
2018-04-20 01:09:03 -03:00
|
|
|
"BEACON_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2021-02-12 23:40:10 -04:00
|
|
|
"MODE_CIRCLE_ENABLED": ["MODE_AUTO_ENABLED", "AP_TERRAIN_AVAILABLE"],
|
2019-08-30 07:42:37 -03:00
|
|
|
"MODE_GUIDED_ENABLED": ["MODE_AUTO_ENABLED",
|
|
|
|
"ADSB_ENABLED",
|
|
|
|
"MODE_FOLLOW_ENABLED",
|
|
|
|
"MODE_GUIDED_NOGPS_ENABLED"],
|
2018-04-20 01:09:03 -03:00
|
|
|
"AC_AVOID_ENABLED": ["MODE_FOLLOW_ENABLED"],
|
|
|
|
},
|
2019-08-29 01:06:00 -03:00
|
|
|
},
|
|
|
|
{
|
|
|
|
"config": 'ArduCopter/config.h',
|
|
|
|
"autotest_target": "build.Helicopter",
|
|
|
|
"target_binary": "bin/arducopter-heli",
|
2019-11-01 02:49:25 -03:00
|
|
|
"blacklist_options": ["TOY_MODE_ENABLED",
|
|
|
|
"MODE_ACRO_ENABLED",
|
|
|
|
"AUTOTUNE_ENABLED"],
|
2019-08-29 01:06:00 -03:00
|
|
|
"reverse-deps": {
|
2022-07-19 08:33:13 -03:00
|
|
|
"AP_FENCE_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2019-08-30 07:42:37 -03:00
|
|
|
"PROXIMITY_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2021-02-12 23:40:10 -04:00
|
|
|
"MODE_AUTO_ENABLED": ["MODE_GUIDED", "ADVANCED_FAILSAFE"],
|
|
|
|
"MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "MODE_SMARTRTL_ENABLED"],
|
2019-08-29 01:06:00 -03:00
|
|
|
"BEACON_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"],
|
2021-02-12 23:40:10 -04:00
|
|
|
"MODE_CIRCLE_ENABLED": ["MODE_AUTO_ENABLED"],
|
2019-11-01 02:49:25 -03:00
|
|
|
"MODE_GUIDED_ENABLED": ["MODE_AUTO_ENABLED",
|
|
|
|
"ADSB_ENABLED",
|
|
|
|
"MODE_FOLLOW_ENABLED",
|
|
|
|
"MODE_GUIDED_NOGPS_ENABLED"],
|
2019-08-29 01:06:00 -03:00
|
|
|
"AC_AVOID_ENABLED": ["MODE_FOLLOW_ENABLED"],
|
|
|
|
},
|
|
|
|
},
|
|
|
|
{
|
2018-04-20 01:09:03 -03:00
|
|
|
"config": 'ArduPlane/config.h',
|
2020-03-26 23:46:12 -03:00
|
|
|
"autotest_target": "build.Plane",
|
2019-08-29 01:06:00 -03:00
|
|
|
"target_binary": "bin/arduplane",
|
2018-04-20 01:09:03 -03:00
|
|
|
"reverse-deps": {
|
|
|
|
},
|
|
|
|
}, {
|
2020-03-26 20:14:17 -03:00
|
|
|
"config": 'Rover/config.h',
|
2020-03-26 23:46:12 -03:00
|
|
|
"autotest_target": "build.Rover",
|
2019-08-29 01:06:00 -03:00
|
|
|
"target_binary": "bin/ardurover",
|
2018-04-20 01:09:03 -03:00
|
|
|
"reverse-deps": {
|
|
|
|
},
|
|
|
|
}, {
|
|
|
|
"config": 'ArduSub/config.h',
|
2020-03-26 23:46:12 -03:00
|
|
|
"autotest_target": "build.Sub",
|
2019-08-29 01:06:00 -03:00
|
|
|
"target_binary": "bin/ardusub",
|
2018-04-20 01:09:03 -03:00
|
|
|
"reverse-deps": {
|
2022-07-19 08:33:13 -03:00
|
|
|
"AP_FENCE_ENABLED": ["AVOIDANCE_ENABLED"],
|
2018-04-20 01:09:03 -03:00
|
|
|
"PROXIMITY_ENABLED": ["AVOIDANCE_ENABLED"],
|
|
|
|
},
|
|
|
|
}, {
|
|
|
|
"config": 'AntennaTracker/config.h',
|
2020-03-26 23:46:12 -03:00
|
|
|
"autotest_target": "build.Tracker",
|
2019-08-29 01:06:00 -03:00
|
|
|
"target_binary": "bin/antennatracker",
|
2018-04-20 01:09:03 -03:00
|
|
|
"reverse-deps": {
|
|
|
|
},
|
2019-08-30 07:42:37 -03:00
|
|
|
},
|
|
|
|
]
|
2019-08-29 01:06:00 -03:00
|
|
|
|
2018-04-20 01:09:03 -03:00
|
|
|
|
2022-01-09 20:06:29 -04:00
|
|
|
if __name__ == '__main__':
|
|
|
|
builders = []
|
2018-04-20 01:09:03 -03:00
|
|
|
|
2022-01-09 20:06:29 -04:00
|
|
|
# append autotest builders:
|
|
|
|
for spec in specs:
|
|
|
|
builder = Builder(spec, autotest=True)
|
2019-08-29 01:06:00 -03:00
|
|
|
builder.run()
|
|
|
|
builders.append(builder)
|
|
|
|
|
2022-01-09 20:06:29 -04:00
|
|
|
# append directly-build-by-waf targets
|
|
|
|
for spec in specs:
|
|
|
|
for board in ["CubeOrange"]:
|
|
|
|
builder = Builder(spec, board=board)
|
|
|
|
builder.run()
|
|
|
|
builders.append(builder)
|
|
|
|
|
|
|
|
print("")
|
|
|
|
for builder in builders:
|
|
|
|
print("Builder: %s" % builder.description())
|
|
|
|
# print(" Successes: %s" % builder.successes)
|
|
|
|
print(" Failures: %s" % builder.failures)
|