autotest: test_build_options.py: add --resume option

This commit is contained in:
Peter Barker 2024-09-01 09:46:55 +10:00 committed by Peter Barker
parent 1439aebf94
commit 4700f09e7d
1 changed files with 34 additions and 2 deletions

View File

@ -24,6 +24,7 @@ import fnmatch
import optparse
import os
import pathlib
import re
import sys
from pysim import util
@ -53,6 +54,7 @@ class TestBuildOptions(object):
board="CubeOrange", # DevEBoxH7v2 also works
extra_hwdef=None,
emit_disable_all_defines=None,
resume=False,
):
self.extra_hwdef = extra_hwdef
self.sizes_nothing_disabled = None
@ -67,6 +69,7 @@ class TestBuildOptions(object):
self.build_targets = self.all_targets()
self._board = board
self.emit_disable_all_defines = emit_disable_all_defines
self.resume = resume
self.results = {}
self.enable_in_turn_results = {}
@ -314,13 +317,19 @@ class TestBuildOptions(object):
f.write(self.csv_for_results(self.results))
def run_disable_in_turn(self):
progress_file = pathlib.Path("/tmp/run-disable-in-turn-progress")
resume_number = self.resume_number_from_progress_Path(progress_file)
options = self.get_build_options_from_ardupilot_tree()
count = 1
for feature in sorted(options, key=lambda x : x.define):
if resume_number is not None:
if count < resume_number:
count += 1
continue
if self.match_glob is not None:
if not fnmatch.fnmatch(feature.define, self.match_glob):
continue
with open("/tmp/run-disable-in-turn-progress", "w") as f:
with open(progress_file, "w") as f:
f.write(f"{count}/{len(options)} {feature.define}\n")
# if feature.define < "WINCH_ENABLED":
# count += 1
@ -351,16 +360,35 @@ class TestBuildOptions(object):
with open("/tmp/enable-in-turn.csv", "w") as f:
f.write(self.csv_for_results(self.enable_in_turn_results))
def resume_number_from_progress_Path(self, progress_file):
if not self.resume:
return None
try:
content = progress_file.read_text().rstrip()
m = re.match(r"(\d+)/\d+ \w+", content)
if m is None:
raise ValueError(f"{progress_file} not matched")
return int(m.group(1))
except FileNotFoundError:
pass
return None
def run_enable_in_turn(self):
progress_file = pathlib.Path("/tmp/run-enable-in-turn-progress")
resume_number = self.resume_number_from_progress_Path(progress_file)
options = self.get_build_options_from_ardupilot_tree()
count = 1
for feature in options:
if resume_number is not None:
if count < resume_number:
count += 1
continue
if self.match_glob is not None:
if not fnmatch.fnmatch(feature.define, self.match_glob):
continue
self.progress("Enabling feature %s(%s) (%u/%u)" %
(feature.label, feature.define, count, len(options)))
with open("/tmp/run-enable-in-turn-progress", "w") as f:
with open(progress_file, "w") as f:
f.write(f"{count}/{len(options)} {feature.define}\n")
self.test_enable_feature(feature, options)
count += 1
@ -487,6 +515,9 @@ if __name__ == '__main__':
parser.add_option("--emit-disable-all-defines",
action='store_true',
help='emit defines used for disabling all features then exit')
parser.add_option("--resume",
action='store_true',
help='resume from previous progress file')
opts, args = parser.parse_args()
@ -501,6 +532,7 @@ if __name__ == '__main__':
board=opts.board,
extra_hwdef=opts.extra_hwdef,
emit_disable_all_defines=opts.emit_disable_all_defines,
resume=opts.resume,
)
tbo.run()