2022-09-14 22:54:50 -03:00
|
|
|
#!/usr/bin/env python3
|
2022-01-09 22:49:20 -04:00
|
|
|
|
|
|
|
"""
|
|
|
|
Contains functions used to test the ArduPilot build_options.py structures
|
|
|
|
|
|
|
|
AP_FLAKE8_CLEAN
|
|
|
|
"""
|
|
|
|
|
|
|
|
from __future__ import print_function
|
|
|
|
|
2022-05-12 00:59:59 -03:00
|
|
|
import fnmatch
|
|
|
|
import optparse
|
2022-01-09 22:49:20 -04:00
|
|
|
import os
|
|
|
|
|
|
|
|
from pysim import util
|
|
|
|
|
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
class TestBuildOptions(object):
|
2022-05-12 00:59:59 -03:00
|
|
|
def __init__(self,
|
|
|
|
match_glob=None,
|
|
|
|
do_step_disable_all=True,
|
|
|
|
do_step_disable_none=False,
|
2022-06-14 03:51:21 -03:00
|
|
|
do_step_disable_defaults=True,
|
|
|
|
do_step_disable_in_turn=True,
|
2022-09-14 22:54:50 -03:00
|
|
|
do_step_enable_in_turn=True,
|
2022-07-19 09:33:01 -03:00
|
|
|
build_targets=None,
|
2022-07-14 23:38:25 -03:00
|
|
|
board="DevEBoxH7v2",
|
|
|
|
extra_hwdef=None):
|
|
|
|
self.extra_hwdef = extra_hwdef
|
2022-03-04 08:06:54 -04:00
|
|
|
self.sizes_nothing_disabled = None
|
2022-05-12 00:59:59 -03:00
|
|
|
self.match_glob = match_glob
|
|
|
|
self.do_step_disable_all = do_step_disable_all
|
|
|
|
self.do_step_disable_none = do_step_disable_none
|
2022-06-14 03:51:21 -03:00
|
|
|
self.do_step_run_with_defaults = do_step_disable_defaults
|
|
|
|
self.do_step_disable_in_turn = do_step_disable_in_turn
|
2022-09-14 22:54:50 -03:00
|
|
|
self.do_step_enable_in_turn = do_step_enable_in_turn
|
2022-05-12 00:59:59 -03:00
|
|
|
self.build_targets = build_targets
|
|
|
|
if self.build_targets is None:
|
|
|
|
self.build_targets = self.all_targets()
|
2022-07-19 09:33:01 -03:00
|
|
|
self._board = board
|
2022-05-12 00:59:59 -03:00
|
|
|
|
|
|
|
@staticmethod
|
|
|
|
def all_targets():
|
|
|
|
return ['copter', 'plane', 'rover', 'antennatracker', 'sub', 'blimp']
|
|
|
|
|
|
|
|
def progress(self, message):
|
|
|
|
print("###### %s" % message)
|
2022-03-04 08:06:54 -04:00
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
# swiped from app.py:
|
|
|
|
def get_build_options_from_ardupilot_tree(self):
|
|
|
|
'''return a list of build options'''
|
|
|
|
import importlib.util
|
|
|
|
spec = importlib.util.spec_from_file_location(
|
|
|
|
"build_options.py",
|
|
|
|
os.path.join(os.path.dirname(os.path.realpath(__file__)),
|
|
|
|
'..', 'scripts', 'build_options.py'))
|
|
|
|
mod = importlib.util.module_from_spec(spec)
|
|
|
|
spec.loader.exec_module(mod)
|
|
|
|
return mod.BUILD_OPTIONS
|
|
|
|
|
|
|
|
def write_defines_to_file(self, defines, filepath):
|
2022-04-14 20:49:56 -03:00
|
|
|
lines = []
|
|
|
|
lines.extend(["undef %s\n" % (a, ) for (a, b) in defines.items()])
|
|
|
|
lines.extend(["define %s %s\n" % (a, b) for (a, b) in defines.items()])
|
|
|
|
content = "".join(lines)
|
2022-03-04 02:33:10 -04:00
|
|
|
with open(filepath, "w") as f:
|
|
|
|
f.write(content)
|
|
|
|
|
2022-09-14 22:54:50 -03:00
|
|
|
def get_disable_defines(self, feature, options):
|
2022-03-04 02:33:10 -04:00
|
|
|
'''returns a hash of (name, value) defines to turn feature off -
|
|
|
|
recursively gets dependencies'''
|
|
|
|
ret = {
|
|
|
|
feature.define: 0,
|
|
|
|
}
|
2022-09-01 23:04:27 -03:00
|
|
|
added_one = True
|
|
|
|
while added_one:
|
|
|
|
added_one = False
|
|
|
|
for option in options:
|
|
|
|
if option.define in ret:
|
|
|
|
continue
|
|
|
|
if option.dependency is None:
|
|
|
|
continue
|
|
|
|
for dep in option.dependency.split(','):
|
|
|
|
f = self.get_option_by_label(dep, options)
|
|
|
|
if f.define not in ret:
|
|
|
|
continue
|
|
|
|
|
|
|
|
print("%s requires %s" % (option.define, f.define))
|
|
|
|
added_one = True
|
|
|
|
ret[option.define] = 0
|
|
|
|
break
|
2022-01-09 22:49:20 -04:00
|
|
|
return ret
|
2022-03-04 02:33:10 -04:00
|
|
|
|
2022-09-14 22:54:50 -03:00
|
|
|
def update_get_enable_defines_for_feature(self, ret, feature, options):
|
|
|
|
'''recursive function to turn on required feature and what it depends
|
|
|
|
on'''
|
|
|
|
ret[feature.define] = 1
|
|
|
|
if feature.dependency is None:
|
|
|
|
return
|
|
|
|
for depname in feature.dependency.split(','):
|
|
|
|
dep = None
|
|
|
|
for f in options:
|
|
|
|
if f.label == depname:
|
|
|
|
dep = f
|
|
|
|
if dep is None:
|
|
|
|
raise ValueError("Invalid dep (%s) for feature (%s)" %
|
|
|
|
(depname, feature.label))
|
|
|
|
self.update_get_enable_defines_for_feature(ret, dep, options)
|
|
|
|
|
|
|
|
def get_enable_defines(self, feature, options):
|
|
|
|
'''returns a hash of (name, value) defines to turn all features *but* feature (and whatever it depends on) on'''
|
|
|
|
ret = self.get_disable_all_defines()
|
|
|
|
self.update_get_enable_defines_for_feature(ret, feature, options)
|
|
|
|
return ret
|
|
|
|
|
|
|
|
def test_disable_feature(self, feature, options):
|
|
|
|
defines = self.get_disable_defines(feature, options)
|
2022-08-27 19:46:13 -03:00
|
|
|
|
|
|
|
if len(defines.keys()) > 1:
|
2022-09-01 23:04:27 -03:00
|
|
|
self.progress("Disabling %s disables (%s)" % (
|
2022-08-27 19:46:13 -03:00
|
|
|
feature.define,
|
|
|
|
",".join(defines.keys())))
|
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
self.test_compile_with_defines(defines)
|
|
|
|
|
2022-09-14 22:54:50 -03:00
|
|
|
def test_enable_feature(self, feature, options):
|
|
|
|
defines = self.get_enable_defines(feature, options)
|
|
|
|
|
|
|
|
enabled = list(filter(lambda x : bool(defines[x]), defines.keys()))
|
|
|
|
|
|
|
|
if len(enabled) > 1:
|
|
|
|
self.progress("Enabling %s enables (%s)" % (
|
|
|
|
feature.define,
|
|
|
|
",".join(enabled)))
|
|
|
|
|
|
|
|
self.test_compile_with_defines(defines)
|
|
|
|
|
2022-03-04 08:06:54 -04:00
|
|
|
def board(self):
|
|
|
|
'''returns board to build for'''
|
2022-07-19 09:33:01 -03:00
|
|
|
return self._board
|
2022-03-04 08:06:54 -04:00
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
def test_compile_with_defines(self, defines):
|
|
|
|
extra_hwdef_filepath = "/tmp/extra.hwdef"
|
|
|
|
self.write_defines_to_file(defines, extra_hwdef_filepath)
|
2022-07-14 23:38:25 -03:00
|
|
|
if self.extra_hwdef is not None:
|
|
|
|
content = open(self.extra_hwdef, "r").read()
|
|
|
|
with open(extra_hwdef_filepath, "a") as f:
|
|
|
|
f.write(content)
|
2022-03-04 02:33:10 -04:00
|
|
|
util.waf_configure(
|
2022-03-04 08:06:54 -04:00
|
|
|
self.board(),
|
2022-03-04 02:33:10 -04:00
|
|
|
extra_hwdef=extra_hwdef_filepath,
|
|
|
|
)
|
2022-05-12 00:59:59 -03:00
|
|
|
for t in self.build_targets:
|
2022-03-04 02:33:10 -04:00
|
|
|
try:
|
2022-03-04 08:06:54 -04:00
|
|
|
util.run_cmd([util.relwaf(), t])
|
2022-03-04 02:33:10 -04:00
|
|
|
except Exception:
|
2022-03-04 08:06:54 -04:00
|
|
|
print("Failed to build (%s) with things disabled" %
|
2022-03-04 02:33:10 -04:00
|
|
|
(t,))
|
|
|
|
raise
|
|
|
|
|
2022-03-04 08:06:54 -04:00
|
|
|
def find_build_sizes(self):
|
|
|
|
'''returns a hash with size of all build targets'''
|
|
|
|
ret = {}
|
|
|
|
target_to_binpath = {
|
|
|
|
"copter": "arducopter",
|
2022-03-12 08:21:55 -04:00
|
|
|
"plane": "arduplane",
|
|
|
|
"rover": "ardurover",
|
|
|
|
"antennatracker": "antennatracker",
|
|
|
|
"sub": "ardusub",
|
|
|
|
"blimp": "blimp",
|
2022-03-04 08:06:54 -04:00
|
|
|
}
|
2022-05-12 00:59:59 -03:00
|
|
|
for target in self.build_targets:
|
2022-03-04 08:06:54 -04:00
|
|
|
path = os.path.join("build", self.board(), "bin", "%s.bin" % target_to_binpath[target])
|
|
|
|
ret[target] = os.path.getsize(path)
|
|
|
|
return ret
|
|
|
|
|
|
|
|
def disable_in_turn_check_sizes(self, feature, sizes_nothing_disabled):
|
2022-05-12 00:59:59 -03:00
|
|
|
if not self.do_step_disable_none:
|
|
|
|
self.progress("disable-none skipped, size comparison not available")
|
|
|
|
return
|
2022-03-04 08:06:54 -04:00
|
|
|
current_sizes = self.find_build_sizes()
|
|
|
|
for (build, new_size) in current_sizes.items():
|
|
|
|
old_size = sizes_nothing_disabled[build]
|
2022-05-12 00:59:59 -03:00
|
|
|
self.progress("Disabling %s(%s) on %s saves %u bytes" %
|
|
|
|
(feature.label, feature.define, build, old_size - new_size))
|
2022-03-04 08:06:54 -04:00
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
def run_disable_in_turn(self):
|
|
|
|
options = self.get_build_options_from_ardupilot_tree()
|
2022-05-12 00:59:59 -03:00
|
|
|
if self.match_glob is not None:
|
|
|
|
options = list(filter(lambda x : fnmatch.fnmatch(x.define, self.match_glob), options))
|
2022-03-04 02:33:10 -04:00
|
|
|
count = 1
|
|
|
|
for feature in options:
|
2022-05-12 00:59:59 -03:00
|
|
|
self.progress("Disabling feature %s(%s) (%u/%u)" %
|
|
|
|
(feature.label, feature.define, count, len(options)))
|
2022-09-14 22:54:50 -03:00
|
|
|
self.test_disable_feature(feature, options)
|
2022-03-04 02:33:10 -04:00
|
|
|
count += 1
|
2022-03-04 08:06:54 -04:00
|
|
|
self.disable_in_turn_check_sizes(feature, self.sizes_nothing_disabled)
|
2022-03-04 02:33:10 -04:00
|
|
|
|
2022-09-14 22:54:50 -03:00
|
|
|
def run_enable_in_turn(self):
|
|
|
|
options = self.get_build_options_from_ardupilot_tree()
|
|
|
|
if self.match_glob is not None:
|
|
|
|
options = list(filter(lambda x : fnmatch.fnmatch(x.define, self.match_glob), options))
|
|
|
|
count = 1
|
|
|
|
for feature in options:
|
|
|
|
self.progress("Enabling feature %s(%s) (%u/%u)" %
|
|
|
|
(feature.label, feature.define, count, len(options)))
|
|
|
|
self.test_enable_feature(feature, options)
|
|
|
|
count += 1
|
|
|
|
|
2022-09-01 23:04:27 -03:00
|
|
|
def get_option_by_label(self, label, options):
|
|
|
|
for x in options:
|
|
|
|
if x.label == label:
|
|
|
|
return x
|
2022-09-15 06:35:39 -03:00
|
|
|
raise ValueError("No such option (%s)" % label)
|
2022-09-01 23:04:27 -03:00
|
|
|
|
2022-09-14 22:54:50 -03:00
|
|
|
def get_disable_all_defines(self):
|
|
|
|
'''returns a hash of defines which turns all features off'''
|
2022-03-04 02:33:10 -04:00
|
|
|
options = self.get_build_options_from_ardupilot_tree()
|
|
|
|
defines = {}
|
|
|
|
for feature in options:
|
2022-05-12 00:59:59 -03:00
|
|
|
if self.match_glob is not None:
|
|
|
|
if not fnmatch.fnmatch(feature.define, self.match_glob):
|
|
|
|
continue
|
2022-03-04 02:33:10 -04:00
|
|
|
defines[feature.define] = 0
|
2022-09-14 22:54:50 -03:00
|
|
|
return defines
|
|
|
|
|
|
|
|
def run_disable_all(self):
|
|
|
|
defines = self.get_disable_all_defines()
|
2022-03-04 02:33:10 -04:00
|
|
|
self.test_compile_with_defines(defines)
|
|
|
|
|
2022-03-04 08:06:54 -04:00
|
|
|
def run_disable_none(self):
|
|
|
|
self.test_compile_with_defines({})
|
|
|
|
self.sizes_nothing_disabled = self.find_build_sizes()
|
|
|
|
|
2022-06-14 03:51:21 -03:00
|
|
|
def run_with_defaults(self):
|
|
|
|
options = self.get_build_options_from_ardupilot_tree()
|
|
|
|
defines = {}
|
|
|
|
for feature in options:
|
|
|
|
defines[feature.define] = feature.default
|
|
|
|
self.test_compile_with_defines(defines)
|
|
|
|
|
2022-08-27 19:46:13 -03:00
|
|
|
def check_deps_consistency(self):
|
|
|
|
# self.progress("Checking deps consistency")
|
|
|
|
options = self.get_build_options_from_ardupilot_tree()
|
|
|
|
for feature in options:
|
2022-09-14 22:54:50 -03:00
|
|
|
self.get_disable_defines(feature, options)
|
2022-08-27 19:46:13 -03:00
|
|
|
|
2022-03-04 02:33:10 -04:00
|
|
|
def run(self):
|
2022-08-27 19:46:13 -03:00
|
|
|
self.check_deps_consistency()
|
2022-06-14 03:51:21 -03:00
|
|
|
if self.do_step_run_with_defaults:
|
|
|
|
self.progress("Running run-with-defaults step")
|
|
|
|
self.run_with_defaults()
|
2022-05-12 00:59:59 -03:00
|
|
|
if self.do_step_disable_all:
|
|
|
|
self.progress("Running disable-all step")
|
|
|
|
self.run_disable_all()
|
|
|
|
if self.do_step_disable_none:
|
|
|
|
self.progress("Running disable-none step")
|
|
|
|
self.run_disable_none()
|
2022-06-14 03:51:21 -03:00
|
|
|
if self.do_step_disable_in_turn:
|
|
|
|
self.progress("Running disable-in-turn step")
|
|
|
|
self.run_disable_in_turn()
|
2022-09-14 22:54:50 -03:00
|
|
|
if self.do_step_enable_in_turn:
|
|
|
|
self.progress("Running enable-in-turn step")
|
|
|
|
self.run_enable_in_turn()
|
2022-01-13 21:18:45 -04:00
|
|
|
|
|
|
|
|
2022-01-09 22:49:20 -04:00
|
|
|
if __name__ == '__main__':
|
2022-05-12 00:59:59 -03:00
|
|
|
|
|
|
|
parser = optparse.OptionParser()
|
|
|
|
parser.add_option("--define-match-glob",
|
|
|
|
type='string',
|
|
|
|
default=None,
|
|
|
|
help='feature define must match this glob to be tested')
|
2022-06-14 03:51:21 -03:00
|
|
|
parser.add_option("--no-run-with-defaults",
|
|
|
|
action='store_true',
|
|
|
|
help='Do not run the run-with-defaults step')
|
2022-05-12 00:59:59 -03:00
|
|
|
parser.add_option("--no-disable-all",
|
|
|
|
action='store_true',
|
|
|
|
help='Do not run the disable-all step')
|
|
|
|
parser.add_option("--no-disable-none",
|
|
|
|
action='store_true',
|
|
|
|
help='Do not run the disable-none step')
|
2022-06-14 03:51:21 -03:00
|
|
|
parser.add_option("--no-disable-in-turn",
|
|
|
|
action='store_true',
|
|
|
|
help='Do not run the disable-in-turn step')
|
2022-09-14 22:54:50 -03:00
|
|
|
parser.add_option("--no-enable-in-turn",
|
|
|
|
action='store_true',
|
|
|
|
help='Do not run the enable-in-turn step')
|
2022-05-12 00:59:59 -03:00
|
|
|
parser.add_option("--build-targets",
|
|
|
|
type='choice',
|
|
|
|
choices=TestBuildOptions.all_targets(),
|
|
|
|
action='append',
|
|
|
|
help='vehicle targets to build')
|
2022-07-14 23:38:25 -03:00
|
|
|
parser.add_option("--extra-hwdef",
|
|
|
|
type='string',
|
|
|
|
default=None,
|
|
|
|
help="file containing extra hwdef information")
|
2022-07-19 09:33:01 -03:00
|
|
|
parser.add_option("--board",
|
|
|
|
type='string',
|
|
|
|
default="DevEBoxH7v2",
|
|
|
|
help='board to build for')
|
2022-05-12 00:59:59 -03:00
|
|
|
|
|
|
|
opts, args = parser.parse_args()
|
|
|
|
|
|
|
|
tbo = TestBuildOptions(
|
|
|
|
match_glob=opts.define_match_glob,
|
|
|
|
do_step_disable_all=not opts.no_disable_all,
|
|
|
|
do_step_disable_none=not opts.no_disable_none,
|
2022-06-14 03:51:21 -03:00
|
|
|
do_step_disable_defaults=not opts.no_run_with_defaults,
|
|
|
|
do_step_disable_in_turn=not opts.no_disable_in_turn,
|
2022-09-14 22:54:50 -03:00
|
|
|
do_step_enable_in_turn=not opts.no_enable_in_turn,
|
2022-05-12 00:59:59 -03:00
|
|
|
build_targets=opts.build_targets,
|
2022-07-19 09:33:01 -03:00
|
|
|
board=opts.board,
|
2022-07-14 23:38:25 -03:00
|
|
|
extra_hwdef=opts.extra_hwdef,
|
2022-05-12 00:59:59 -03:00
|
|
|
)
|
2022-03-04 02:33:10 -04:00
|
|
|
tbo.run()
|