mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
scripts: update size_compare from master
This commit is contained in:
parent
b2b81f0878
commit
e0a0b9e736
@ -17,16 +17,24 @@ Output is placed into ../ELF_DIFF_[VEHICLE_NAME]
|
|||||||
'''
|
'''
|
||||||
|
|
||||||
import copy
|
import copy
|
||||||
|
import fnmatch
|
||||||
import optparse
|
import optparse
|
||||||
import os
|
import os
|
||||||
|
import pathlib
|
||||||
import shutil
|
import shutil
|
||||||
import string
|
import string
|
||||||
import subprocess
|
import subprocess
|
||||||
import sys
|
import sys
|
||||||
import tempfile
|
import tempfile
|
||||||
|
import threading
|
||||||
import time
|
import time
|
||||||
import board_list
|
import board_list
|
||||||
|
|
||||||
|
try:
|
||||||
|
import queue as Queue
|
||||||
|
except ImportError:
|
||||||
|
import Queue
|
||||||
|
|
||||||
if sys.version_info[0] < 3:
|
if sys.version_info[0] < 3:
|
||||||
running_python3 = False
|
running_python3 = False
|
||||||
else:
|
else:
|
||||||
@ -54,15 +62,20 @@ class SizeCompareBranches(object):
|
|||||||
bin_dir=None,
|
bin_dir=None,
|
||||||
run_elf_diff=True,
|
run_elf_diff=True,
|
||||||
all_vehicles=False,
|
all_vehicles=False,
|
||||||
|
exclude_board_glob=[],
|
||||||
all_boards=False,
|
all_boards=False,
|
||||||
use_merge_base=True,
|
use_merge_base=True,
|
||||||
waf_consistent_builds=True,
|
waf_consistent_builds=True,
|
||||||
show_empty=True,
|
show_empty=True,
|
||||||
|
show_unchanged=True,
|
||||||
extra_hwdef=[],
|
extra_hwdef=[],
|
||||||
extra_hwdef_branch=[],
|
extra_hwdef_branch=[],
|
||||||
extra_hwdef_master=[]):
|
extra_hwdef_master=[],
|
||||||
|
parallel_copies=None,
|
||||||
|
jobs=None):
|
||||||
|
|
||||||
if branch is None:
|
if branch is None:
|
||||||
branch = self.find_current_git_branch()
|
branch = self.find_current_git_branch_or_sha1()
|
||||||
|
|
||||||
self.master_branch = master_branch
|
self.master_branch = master_branch
|
||||||
self.branch = branch
|
self.branch = branch
|
||||||
@ -78,6 +91,9 @@ class SizeCompareBranches(object):
|
|||||||
self.use_merge_base = use_merge_base
|
self.use_merge_base = use_merge_base
|
||||||
self.waf_consistent_builds = waf_consistent_builds
|
self.waf_consistent_builds = waf_consistent_builds
|
||||||
self.show_empty = show_empty
|
self.show_empty = show_empty
|
||||||
|
self.show_unchanged = show_unchanged
|
||||||
|
self.parallel_copies = parallel_copies
|
||||||
|
self.jobs = jobs
|
||||||
|
|
||||||
if self.bin_dir is None:
|
if self.bin_dir is None:
|
||||||
self.bin_dir = self.find_bin_dir()
|
self.bin_dir = self.find_bin_dir()
|
||||||
@ -116,10 +132,23 @@ class SizeCompareBranches(object):
|
|||||||
if v not in self.vehicle_map.keys():
|
if v not in self.vehicle_map.keys():
|
||||||
raise ValueError("Bad vehicle (%s); choose from %s" % (v, ",".join(self.vehicle_map.keys())))
|
raise ValueError("Bad vehicle (%s); choose from %s" % (v, ",".join(self.vehicle_map.keys())))
|
||||||
|
|
||||||
|
# remove boards based on --exclude-board-glob
|
||||||
|
new_self_board = []
|
||||||
|
for board_name in self.board:
|
||||||
|
exclude = False
|
||||||
|
for exclude_glob in exclude_board_glob:
|
||||||
|
if fnmatch.fnmatch(board_name, exclude_glob):
|
||||||
|
exclude = True
|
||||||
|
break
|
||||||
|
if not exclude:
|
||||||
|
new_self_board.append(board_name)
|
||||||
|
self.board = new_self_board
|
||||||
|
|
||||||
# some boards we don't have a -bl.dat for, so skip them.
|
# some boards we don't have a -bl.dat for, so skip them.
|
||||||
# TODO: find a way to get this information from board_list:
|
# TODO: find a way to get this information from board_list:
|
||||||
self.bootloader_blacklist = set([
|
self.bootloader_blacklist = set([
|
||||||
'CubeOrange-SimOnHardWare',
|
'CubeOrange-SimOnHardWare',
|
||||||
|
'CubeOrangePlus-SimOnHardWare',
|
||||||
'fmuv2',
|
'fmuv2',
|
||||||
'fmuv3-bdshot',
|
'fmuv3-bdshot',
|
||||||
'iomcu',
|
'iomcu',
|
||||||
@ -130,7 +159,9 @@ class SizeCompareBranches(object):
|
|||||||
'skyviper-f412-rev1',
|
'skyviper-f412-rev1',
|
||||||
'skyviper-journey',
|
'skyviper-journey',
|
||||||
'Pixhawk1-1M-bdshot',
|
'Pixhawk1-1M-bdshot',
|
||||||
|
'Pixhawk1-bdshot',
|
||||||
'SITL_arm_linux_gnueabihf',
|
'SITL_arm_linux_gnueabihf',
|
||||||
|
'RADIX2HD',
|
||||||
])
|
])
|
||||||
|
|
||||||
# blacklist all linux boards for bootloader build:
|
# blacklist all linux boards for bootloader build:
|
||||||
@ -170,6 +201,9 @@ class SizeCompareBranches(object):
|
|||||||
return [
|
return [
|
||||||
'esp32buzz',
|
'esp32buzz',
|
||||||
'esp32empty',
|
'esp32empty',
|
||||||
|
'esp32tomte76',
|
||||||
|
'esp32nick',
|
||||||
|
'esp32s3devkit',
|
||||||
'esp32icarous',
|
'esp32icarous',
|
||||||
'esp32diy',
|
'esp32diy',
|
||||||
]
|
]
|
||||||
@ -183,15 +217,21 @@ class SizeCompareBranches(object):
|
|||||||
|
|
||||||
# vast amounts of stuff copied into here from build_binaries.py
|
# vast amounts of stuff copied into here from build_binaries.py
|
||||||
|
|
||||||
def run_program(self, prefix, cmd_list, show_output=True, env=None):
|
def run_program(self, prefix, cmd_list, show_output=True, env=None, show_output_on_error=True, show_command=None, cwd="."):
|
||||||
if show_output:
|
if show_command is None:
|
||||||
self.progress("Running (%s)" % " ".join(cmd_list))
|
show_command = True
|
||||||
|
if show_command:
|
||||||
|
cmd = " ".join(cmd_list)
|
||||||
|
if cwd is None:
|
||||||
|
cwd = "."
|
||||||
|
self.progress(f"Running ({cmd}) in ({cwd})")
|
||||||
p = subprocess.Popen(
|
p = subprocess.Popen(
|
||||||
cmd_list,
|
cmd_list,
|
||||||
stdin=None,
|
stdin=None,
|
||||||
stdout=subprocess.PIPE,
|
stdout=subprocess.PIPE,
|
||||||
close_fds=True,
|
close_fds=True,
|
||||||
stderr=subprocess.STDOUT,
|
stderr=subprocess.STDOUT,
|
||||||
|
cwd=cwd,
|
||||||
env=env)
|
env=env)
|
||||||
output = ""
|
output = ""
|
||||||
while True:
|
while True:
|
||||||
@ -209,18 +249,33 @@ class SizeCompareBranches(object):
|
|||||||
x = "".join([chr(c) for c in x])
|
x = "".join([chr(c) for c in x])
|
||||||
output += x
|
output += x
|
||||||
x = x.rstrip()
|
x = x.rstrip()
|
||||||
|
some_output = "%s: %s" % (prefix, x)
|
||||||
if show_output:
|
if show_output:
|
||||||
print("%s: %s" % (prefix, x))
|
print(some_output)
|
||||||
|
else:
|
||||||
|
output += some_output
|
||||||
(_, status) = returncode
|
(_, status) = returncode
|
||||||
if status != 0:
|
if status != 0:
|
||||||
|
if not show_output and show_output_on_error:
|
||||||
|
# we were told not to show output, but we just
|
||||||
|
# failed... so show output...
|
||||||
|
print(output)
|
||||||
self.progress("Process failed (%s)" %
|
self.progress("Process failed (%s)" %
|
||||||
str(returncode))
|
str(returncode))
|
||||||
raise subprocess.CalledProcessError(
|
raise subprocess.CalledProcessError(
|
||||||
returncode, cmd_list)
|
returncode, cmd_list)
|
||||||
return output
|
return output
|
||||||
|
|
||||||
def find_current_git_branch(self):
|
def find_current_git_branch_or_sha1(self):
|
||||||
output = self.run_git(["symbolic-ref", "--short", "HEAD"])
|
try:
|
||||||
|
output = self.run_git(["symbolic-ref", "--short", "HEAD"])
|
||||||
|
output = output.strip()
|
||||||
|
return output
|
||||||
|
except subprocess.CalledProcessError:
|
||||||
|
pass
|
||||||
|
|
||||||
|
# probably in a detached-head state. Get a sha1 instead:
|
||||||
|
output = self.run_git(["rev-parse", "--short", "HEAD"])
|
||||||
output = output.strip()
|
output = output.strip()
|
||||||
return output
|
return output
|
||||||
|
|
||||||
@ -229,13 +284,13 @@ class SizeCompareBranches(object):
|
|||||||
output = output.strip()
|
output = output.strip()
|
||||||
return output
|
return output
|
||||||
|
|
||||||
def run_git(self, args):
|
def run_git(self, args, show_output=True, source_dir=None):
|
||||||
'''run git with args git_args; returns git's output'''
|
'''run git with args git_args; returns git's output'''
|
||||||
cmd_list = ["git"]
|
cmd_list = ["git"]
|
||||||
cmd_list.extend(args)
|
cmd_list.extend(args)
|
||||||
return self.run_program("SCB-GIT", cmd_list)
|
return self.run_program("SCB-GIT", cmd_list, show_output=show_output, cwd=source_dir)
|
||||||
|
|
||||||
def run_waf(self, args, compiler=None):
|
def run_waf(self, args, compiler=None, show_output=True, source_dir=None):
|
||||||
# try to modify the environment so we can consistent builds:
|
# try to modify the environment so we can consistent builds:
|
||||||
consistent_build_envs = {
|
consistent_build_envs = {
|
||||||
"CHIBIOS_GIT_VERSION": "12345678",
|
"CHIBIOS_GIT_VERSION": "12345678",
|
||||||
@ -264,16 +319,19 @@ class SizeCompareBranches(object):
|
|||||||
env["CXX"] = "ccache arm-none-eabi-g++"
|
env["CXX"] = "ccache arm-none-eabi-g++"
|
||||||
else:
|
else:
|
||||||
raise Exception("BB-WAF: Missing compiler %s" % gcc_path)
|
raise Exception("BB-WAF: Missing compiler %s" % gcc_path)
|
||||||
self.run_program("SCB-WAF", cmd_list, env=env)
|
self.run_program("SCB-WAF", cmd_list, env=env, show_output=show_output, cwd=source_dir)
|
||||||
|
|
||||||
def progress(self, string):
|
def progress(self, string):
|
||||||
'''pretty-print progress'''
|
'''pretty-print progress'''
|
||||||
print("SCB: %s" % string)
|
print("SCB: %s" % string)
|
||||||
|
|
||||||
def build_branch_into_dir(self, board, branch, vehicle, outdir, extra_hwdef=None):
|
def build_branch_into_dir(self, board, branch, vehicle, outdir, source_dir=None, extra_hwdef=None, jobs=None):
|
||||||
self.run_git(["checkout", branch])
|
self.run_git(["checkout", branch], show_output=False, source_dir=source_dir)
|
||||||
self.run_git(["submodule", "update", "--recursive"])
|
self.run_git(["submodule", "update", "--recursive"], show_output=False, source_dir=source_dir)
|
||||||
shutil.rmtree("build", ignore_errors=True)
|
build_dir = "build"
|
||||||
|
if source_dir is not None:
|
||||||
|
build_dir = os.path.join(source_dir, "build")
|
||||||
|
shutil.rmtree(build_dir, ignore_errors=True)
|
||||||
waf_configure_args = ["configure", "--board", board]
|
waf_configure_args = ["configure", "--board", board]
|
||||||
if self.waf_consistent_builds:
|
if self.waf_consistent_builds:
|
||||||
waf_configure_args.append("--consistent-builds")
|
waf_configure_args.append("--consistent-builds")
|
||||||
@ -281,14 +339,22 @@ class SizeCompareBranches(object):
|
|||||||
if extra_hwdef is not None:
|
if extra_hwdef is not None:
|
||||||
waf_configure_args.extend(["--extra-hwdef", extra_hwdef])
|
waf_configure_args.extend(["--extra-hwdef", extra_hwdef])
|
||||||
|
|
||||||
self.run_waf(waf_configure_args)
|
if self.run_elf_diff:
|
||||||
|
waf_configure_args.extend(["--debug-symbols"])
|
||||||
|
|
||||||
|
if jobs is None:
|
||||||
|
jobs = self.jobs
|
||||||
|
if jobs is not None:
|
||||||
|
waf_configure_args.extend(["-j", str(jobs)])
|
||||||
|
|
||||||
|
self.run_waf(waf_configure_args, show_output=False, source_dir=source_dir)
|
||||||
# we can't run `./waf copter blimp plane` without error, so do
|
# we can't run `./waf copter blimp plane` without error, so do
|
||||||
# them one-at-a-time:
|
# them one-at-a-time:
|
||||||
for v in vehicle:
|
for v in vehicle:
|
||||||
if v == 'bootloader':
|
if v == 'bootloader':
|
||||||
# need special configuration directive
|
# need special configuration directive
|
||||||
continue
|
continue
|
||||||
self.run_waf([v])
|
self.run_waf([v], show_output=False, source_dir=source_dir)
|
||||||
for v in vehicle:
|
for v in vehicle:
|
||||||
if v != 'bootloader':
|
if v != 'bootloader':
|
||||||
continue
|
continue
|
||||||
@ -297,19 +363,233 @@ class SizeCompareBranches(object):
|
|||||||
# need special configuration directive
|
# need special configuration directive
|
||||||
bootloader_waf_configure_args = copy.copy(waf_configure_args)
|
bootloader_waf_configure_args = copy.copy(waf_configure_args)
|
||||||
bootloader_waf_configure_args.append('--bootloader')
|
bootloader_waf_configure_args.append('--bootloader')
|
||||||
self.run_waf(bootloader_waf_configure_args)
|
# hopefully temporary hack so you can build bootloader
|
||||||
self.run_waf([v])
|
# after building other vehicles without a clean:
|
||||||
self.run_program("rsync", ["rsync", "-aP", "build/", outdir])
|
dsdl_generated_path = os.path.join('build', board, "modules", "DroneCAN", "libcanard", "dsdlc_generated")
|
||||||
|
self.progress("HACK: Removing (%s)" % dsdl_generated_path)
|
||||||
|
if source_dir is not None:
|
||||||
|
dsdl_generated_path = os.path.join(source_dir, dsdl_generated_path)
|
||||||
|
shutil.rmtree(dsdl_generated_path, ignore_errors=True)
|
||||||
|
self.run_waf(bootloader_waf_configure_args, show_output=False, source_dir=source_dir)
|
||||||
|
self.run_waf([v], show_output=False, source_dir=source_dir)
|
||||||
|
self.run_program("rsync", ["rsync", "-ap", "build/", outdir], cwd=source_dir)
|
||||||
|
if source_dir is not None:
|
||||||
|
pathlib.Path(outdir, "scb_sourcepath.txt").write_text(source_dir)
|
||||||
|
|
||||||
|
def vehicles_to_build_for_board_info(self, board_info):
|
||||||
|
vehicles_to_build = []
|
||||||
|
for vehicle in self.vehicle:
|
||||||
|
if vehicle == 'AP_Periph':
|
||||||
|
if not board_info.is_ap_periph:
|
||||||
|
continue
|
||||||
|
else:
|
||||||
|
if board_info.is_ap_periph:
|
||||||
|
continue
|
||||||
|
# the bootloader target isn't an autobuild target, so
|
||||||
|
# it gets special treatment here:
|
||||||
|
if vehicle != 'bootloader' and vehicle.lower() not in [x.lower() for x in board_info.autobuild_targets]:
|
||||||
|
continue
|
||||||
|
vehicles_to_build.append(vehicle)
|
||||||
|
|
||||||
|
return vehicles_to_build
|
||||||
|
|
||||||
|
def parallel_thread_main(self, thread_number):
|
||||||
|
# initialisation; make a copy of the source directory
|
||||||
|
my_source_dir = os.path.join(self.tmpdir, f"thread-{thread_number}-source")
|
||||||
|
self.run_program("rsync", [
|
||||||
|
"rsync",
|
||||||
|
"--exclude=build/",
|
||||||
|
"-ap",
|
||||||
|
"./",
|
||||||
|
my_source_dir
|
||||||
|
])
|
||||||
|
|
||||||
|
while True:
|
||||||
|
try:
|
||||||
|
task = self.parallel_tasks.pop(0)
|
||||||
|
except IndexError:
|
||||||
|
break
|
||||||
|
jobs = None
|
||||||
|
if self.jobs is not None:
|
||||||
|
jobs = int(self.jobs / self.num_threads_remaining)
|
||||||
|
if jobs <= 0:
|
||||||
|
jobs = 1
|
||||||
|
try:
|
||||||
|
self.run_build_task(task, source_dir=my_source_dir, jobs=jobs)
|
||||||
|
except Exception as ex:
|
||||||
|
self.thread_exit_result_queue.put(f"{task}")
|
||||||
|
raise ex
|
||||||
|
|
||||||
|
def check_result_queue(self):
|
||||||
|
while True:
|
||||||
|
try:
|
||||||
|
result = self.thread_exit_result_queue.get_nowait()
|
||||||
|
except Queue.Empty:
|
||||||
|
break
|
||||||
|
if result is None:
|
||||||
|
continue
|
||||||
|
self.failure_exceptions.append(result)
|
||||||
|
|
||||||
|
def run_build_tasks_in_parallel(self, tasks):
|
||||||
|
n_threads = self.parallel_copies
|
||||||
|
if len(tasks) < n_threads:
|
||||||
|
n_threads = len(tasks)
|
||||||
|
self.num_threads_remaining = n_threads
|
||||||
|
|
||||||
|
# shared list for the threads:
|
||||||
|
self.parallel_tasks = copy.copy(tasks) # make this an argument instead?!
|
||||||
|
threads = []
|
||||||
|
self.thread_exit_result_queue = Queue.Queue()
|
||||||
|
for i in range(0, n_threads):
|
||||||
|
t = threading.Thread(
|
||||||
|
target=self.parallel_thread_main,
|
||||||
|
name=f'task-builder-{i}',
|
||||||
|
args=[i],
|
||||||
|
)
|
||||||
|
t.start()
|
||||||
|
threads.append(t)
|
||||||
|
tstart = time.time()
|
||||||
|
self.failure_exceptions = []
|
||||||
|
|
||||||
|
while len(threads):
|
||||||
|
|
||||||
|
self.check_result_queue()
|
||||||
|
|
||||||
|
new_threads = []
|
||||||
|
for thread in threads:
|
||||||
|
thread.join(0)
|
||||||
|
if thread.is_alive():
|
||||||
|
new_threads.append(thread)
|
||||||
|
threads = new_threads
|
||||||
|
self.num_threads_remaining = len(threads)
|
||||||
|
self.progress(
|
||||||
|
f"remaining-tasks={len(self.parallel_tasks)} " +
|
||||||
|
f"remaining-threads={len(threads)} failed-threads={len(self.failure_exceptions)} elapsed={int(time.time() - tstart)}s") # noqa
|
||||||
|
|
||||||
|
# write out a progress CSV:
|
||||||
|
task_results = []
|
||||||
|
for task in tasks:
|
||||||
|
task_results.append(self.gather_results_for_task(task))
|
||||||
|
# progress CSV:
|
||||||
|
with open("/tmp/some.csv", "w") as f:
|
||||||
|
f.write(self.csv_for_results(self.compare_task_results(task_results, no_elf_diff=True)))
|
||||||
|
|
||||||
|
time.sleep(1)
|
||||||
|
self.progress("All threads returned")
|
||||||
|
|
||||||
|
self.check_result_queue()
|
||||||
|
|
||||||
|
if len(self.failure_exceptions):
|
||||||
|
self.progress("Some threads failed:")
|
||||||
|
for ex in self.failure_exceptions:
|
||||||
|
print("Thread failure: %s" % str(ex))
|
||||||
|
|
||||||
def run_all(self):
|
def run_all(self):
|
||||||
'''run tests for boards and vehicles passed in constructor'''
|
'''run tests for boards and vehicles passed in constructor'''
|
||||||
|
|
||||||
results = {}
|
tmpdir = tempfile.mkdtemp()
|
||||||
|
self.tmpdir = tmpdir
|
||||||
|
|
||||||
|
self.master_commit = self.master_branch
|
||||||
|
if self.use_merge_base:
|
||||||
|
self.master_commit = self.find_git_branch_merge_base(self.branch, self.master_branch)
|
||||||
|
self.progress("Using merge base (%s)" % self.master_commit)
|
||||||
|
|
||||||
|
# create an array of tasks to run:
|
||||||
|
tasks = []
|
||||||
for board in self.board:
|
for board in self.board:
|
||||||
vehicle_results = self.run_board(board)
|
board_info = self.boards_by_name[board]
|
||||||
results[board] = vehicle_results
|
|
||||||
with open("/tmp/some.csv", "w") as f:
|
vehicles_to_build = self.vehicles_to_build_for_board_info(board_info)
|
||||||
f.write(self.csv_for_results(results))
|
|
||||||
|
outdir_1 = os.path.join(tmpdir, "out-master-%s" % (board,))
|
||||||
|
tasks.append((board, self.master_commit, outdir_1, vehicles_to_build, self.extra_hwdef_master))
|
||||||
|
outdir_2 = os.path.join(tmpdir, "out-branch-%s" % (board,))
|
||||||
|
tasks.append((board, self.branch, outdir_2, vehicles_to_build, self.extra_hwdef_branch))
|
||||||
|
self.tasks = tasks
|
||||||
|
|
||||||
|
if self.parallel_copies is not None:
|
||||||
|
self.run_build_tasks_in_parallel(tasks)
|
||||||
|
task_results = []
|
||||||
|
for task in tasks:
|
||||||
|
task_results.append(self.gather_results_for_task(task))
|
||||||
|
else:
|
||||||
|
# traditional build everything in sequence:
|
||||||
|
task_results = []
|
||||||
|
for task in tasks:
|
||||||
|
self.run_build_task(task)
|
||||||
|
task_results.append(self.gather_results_for_task(task))
|
||||||
|
|
||||||
|
# progress CSV:
|
||||||
|
with open("/tmp/some.csv", "w") as f:
|
||||||
|
f.write(self.csv_for_results(self.compare_task_results(task_results, no_elf_diff=True)))
|
||||||
|
|
||||||
|
return self.compare_task_results(task_results)
|
||||||
|
|
||||||
|
def elf_diff_results(self, result_master, result_branch):
|
||||||
|
master_branch = result_master["branch"]
|
||||||
|
branch = result_branch["branch"]
|
||||||
|
for vehicle in result_master["vehicle"].keys():
|
||||||
|
elf_filename = result_master["vehicle"][vehicle]["elf_filename"]
|
||||||
|
master_elf_dir = result_master["vehicle"][vehicle]["elf_dir"]
|
||||||
|
new_elf_dir = result_branch["vehicle"][vehicle]["elf_dir"]
|
||||||
|
board = result_master["board"]
|
||||||
|
self.progress("Starting compare (~10 minutes!)")
|
||||||
|
elf_diff_commandline = [
|
||||||
|
"time",
|
||||||
|
"python3",
|
||||||
|
"-m", "elf_diff",
|
||||||
|
"--bin_dir", self.bin_dir,
|
||||||
|
'--bin_prefix=arm-none-eabi-',
|
||||||
|
"--old_alias", "%s %s" % (master_branch, elf_filename),
|
||||||
|
"--new_alias", "%s %s" % (branch, elf_filename),
|
||||||
|
"--html_dir", "../ELF_DIFF_%s_%s" % (board, vehicle),
|
||||||
|
]
|
||||||
|
|
||||||
|
try:
|
||||||
|
master_source_prefix = result_master["vehicle"][vehicle]["source_path"]
|
||||||
|
branch_source_prefix = result_branch["vehicle"][vehicle]["source_path"]
|
||||||
|
elf_diff_commandline.extend([
|
||||||
|
"--old_source_prefix", master_source_prefix,
|
||||||
|
"--new_source_prefix", branch_source_prefix,
|
||||||
|
])
|
||||||
|
except KeyError:
|
||||||
|
pass
|
||||||
|
|
||||||
|
elf_diff_commandline.extend([
|
||||||
|
os.path.join(master_elf_dir, elf_filename),
|
||||||
|
os.path.join(new_elf_dir, elf_filename)
|
||||||
|
])
|
||||||
|
|
||||||
|
self.run_program("SCB", elf_diff_commandline)
|
||||||
|
|
||||||
|
def compare_task_results(self, task_results, no_elf_diff=False):
|
||||||
|
# pair off results, master and branch:
|
||||||
|
pairs = {}
|
||||||
|
for res in task_results:
|
||||||
|
board = res["board"]
|
||||||
|
if board not in pairs:
|
||||||
|
pairs[board] = {}
|
||||||
|
if res["branch"] == self.master_commit:
|
||||||
|
pairs[board]["master"] = res
|
||||||
|
elif res["branch"] == self.branch:
|
||||||
|
pairs[board]["branch"] = res
|
||||||
|
else:
|
||||||
|
raise ValueError(res["branch"])
|
||||||
|
|
||||||
|
results = {}
|
||||||
|
for pair in pairs.values():
|
||||||
|
if "master" not in pair or "branch" not in pair:
|
||||||
|
# probably incomplete:
|
||||||
|
continue
|
||||||
|
master = pair["master"]
|
||||||
|
board = master["board"]
|
||||||
|
try:
|
||||||
|
results[board] = self.compare_results(master, pair["branch"])
|
||||||
|
if self.run_elf_diff and not no_elf_diff:
|
||||||
|
self.elf_diff_results(master, pair["branch"])
|
||||||
|
except FileNotFoundError:
|
||||||
|
pass
|
||||||
|
|
||||||
return results
|
return results
|
||||||
|
|
||||||
@ -342,6 +622,11 @@ class SizeCompareBranches(object):
|
|||||||
if not self.show_empty:
|
if not self.show_empty:
|
||||||
if len(list(filter(lambda x : x != "", line[1:]))) == 0:
|
if len(list(filter(lambda x : x != "", line[1:]))) == 0:
|
||||||
continue
|
continue
|
||||||
|
# do not add to ret value if all output binaries are identical:
|
||||||
|
if not self.show_unchanged:
|
||||||
|
starcount = len(list(filter(lambda x : x == "*", line[1:])))
|
||||||
|
if len(line[1:]) == starcount:
|
||||||
|
continue
|
||||||
ret += ",".join(line) + "\n"
|
ret += ",".join(line) + "\n"
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
@ -375,96 +660,75 @@ class SizeCompareBranches(object):
|
|||||||
|
|
||||||
return f.name
|
return f.name
|
||||||
|
|
||||||
def run_board(self, board):
|
def run_build_task(self, task, source_dir=None, jobs=None):
|
||||||
ret = {}
|
(board, commitish, outdir, vehicles_to_build, extra_hwdef_file) = task
|
||||||
board_info = self.boards_by_name[board]
|
|
||||||
|
|
||||||
vehicles_to_build = []
|
|
||||||
for vehicle in self.vehicle:
|
|
||||||
if vehicle == 'AP_Periph':
|
|
||||||
if not board_info.is_ap_periph:
|
|
||||||
continue
|
|
||||||
else:
|
|
||||||
if board_info.is_ap_periph:
|
|
||||||
continue
|
|
||||||
# the bootloader target isn't an autobuild target, so
|
|
||||||
# it gets special treatment here:
|
|
||||||
if vehicle != 'bootloader' and vehicle.lower() not in [x.lower() for x in board_info.autobuild_targets]:
|
|
||||||
continue
|
|
||||||
vehicles_to_build.append(vehicle)
|
|
||||||
if len(vehicles_to_build) == 0:
|
|
||||||
return ret
|
|
||||||
|
|
||||||
tmpdir = tempfile.mkdtemp()
|
|
||||||
outdir_1 = os.path.join(tmpdir, "out-master-%s" % (board,))
|
|
||||||
outdir_2 = os.path.join(tmpdir, "out-branch-%s" % (board,))
|
|
||||||
|
|
||||||
self.progress("Building branch 1 (%s)" % self.master_branch)
|
|
||||||
master_commit = self.master_branch
|
|
||||||
if self.use_merge_base:
|
|
||||||
master_commit = self.find_git_branch_merge_base(self.branch, self.master_branch)
|
|
||||||
self.progress("Using merge base (%s)" % master_commit)
|
|
||||||
shutil.rmtree(outdir_1, ignore_errors=True)
|
|
||||||
|
|
||||||
|
self.progress(f"Building {task}")
|
||||||
|
shutil.rmtree(outdir, ignore_errors=True)
|
||||||
self.build_branch_into_dir(
|
self.build_branch_into_dir(
|
||||||
board,
|
board,
|
||||||
master_commit,
|
commitish,
|
||||||
vehicles_to_build,
|
vehicles_to_build,
|
||||||
outdir_1,
|
outdir,
|
||||||
extra_hwdef=self.extra_hwdef_file(self.extra_hwdef_master)
|
source_dir=source_dir,
|
||||||
|
extra_hwdef=self.extra_hwdef_file(extra_hwdef_file),
|
||||||
|
jobs=jobs,
|
||||||
)
|
)
|
||||||
|
|
||||||
self.progress("Building branch 2 (%s)" % self.branch)
|
def gather_results_for_task(self, task):
|
||||||
shutil.rmtree(outdir_2, ignore_errors=True)
|
(board, commitish, outdir, vehicles_to_build, extra_hwdef_file) = task
|
||||||
self.build_branch_into_dir(
|
|
||||||
board,
|
result = {
|
||||||
self.branch,
|
"board": board,
|
||||||
vehicles_to_build,
|
"branch": commitish,
|
||||||
outdir_2,
|
"vehicle": {},
|
||||||
self.extra_hwdef_file(self.extra_hwdef_branch)
|
}
|
||||||
)
|
|
||||||
|
have_source_trees = self.parallel_copies is not None and len(self.tasks) <= self.parallel_copies
|
||||||
|
|
||||||
for vehicle in vehicles_to_build:
|
for vehicle in vehicles_to_build:
|
||||||
if vehicle == 'bootloader' and board in self.bootloader_blacklist:
|
if vehicle == 'bootloader' and board in self.bootloader_blacklist:
|
||||||
continue
|
continue
|
||||||
|
|
||||||
elf_filename = self.vehicle_map[vehicle]
|
result["vehicle"][vehicle] = {}
|
||||||
bin_filename = self.vehicle_map[vehicle] + '.bin'
|
v = result["vehicle"][vehicle]
|
||||||
|
v["bin_filename"] = self.vehicle_map[vehicle] + '.bin'
|
||||||
|
|
||||||
if self.run_elf_diff:
|
elf_dirname = "bin"
|
||||||
master_elf_dirname = "bin"
|
if vehicle == 'bootloader':
|
||||||
new_elf_dirname = "bin"
|
# elfs for bootloaders are in the bootloader directory...
|
||||||
if vehicle == 'bootloader':
|
elf_dirname = "bootloader"
|
||||||
# elfs for bootloaders are in the bootloader directory...
|
elf_basedir = outdir
|
||||||
master_elf_dirname = "bootloader"
|
if have_source_trees:
|
||||||
new_elf_dirname = "bootloader"
|
try:
|
||||||
master_elf_dir = os.path.join(outdir_1, board, master_elf_dirname)
|
v["source_path"] = pathlib.Path(outdir, "scb_sourcepath.txt").read_text()
|
||||||
new_elf_dir = os.path.join(outdir_2, board, new_elf_dirname)
|
elf_basedir = os.path.join(v["source_path"], 'build')
|
||||||
self.progress("Starting compare (~10 minutes!)")
|
self.progress("Have source trees")
|
||||||
elf_diff_commandline = [
|
except FileNotFoundError:
|
||||||
"time",
|
pass
|
||||||
"python3",
|
v["bin_dir"] = os.path.join(elf_basedir, board, "bin")
|
||||||
"-m", "elf_diff",
|
elf_dir = os.path.join(elf_basedir, board, elf_dirname)
|
||||||
"--bin_dir", self.bin_dir,
|
v["elf_dir"] = elf_dir
|
||||||
'--bin_prefix=arm-none-eabi-',
|
v["elf_filename"] = self.vehicle_map[vehicle]
|
||||||
"--old_alias", "%s %s" % (self.master_branch, elf_filename),
|
|
||||||
"--new_alias", "%s %s" % (self.branch, elf_filename),
|
|
||||||
"--html_dir", "../ELF_DIFF_%s_%s" % (board, vehicle),
|
|
||||||
os.path.join(master_elf_dir, elf_filename),
|
|
||||||
os.path.join(new_elf_dir, elf_filename)
|
|
||||||
]
|
|
||||||
|
|
||||||
self.run_program("SCB", elf_diff_commandline)
|
return result
|
||||||
|
|
||||||
master_bin_dir = os.path.join(outdir_1, board, "bin")
|
def compare_results(self, result_master, result_branch):
|
||||||
new_bin_dir = os.path.join(outdir_2, board, "bin")
|
ret = {}
|
||||||
|
for vehicle in result_master["vehicle"].keys():
|
||||||
|
# check for the difference in size (and identicality)
|
||||||
|
# of the two binaries:
|
||||||
|
master_bin_dir = result_master["vehicle"][vehicle]["bin_dir"]
|
||||||
|
new_bin_dir = result_branch["vehicle"][vehicle]["bin_dir"]
|
||||||
|
|
||||||
try:
|
try:
|
||||||
|
bin_filename = result_master["vehicle"][vehicle]["bin_filename"]
|
||||||
master_path = os.path.join(master_bin_dir, bin_filename)
|
master_path = os.path.join(master_bin_dir, bin_filename)
|
||||||
new_path = os.path.join(new_bin_dir, bin_filename)
|
new_path = os.path.join(new_bin_dir, bin_filename)
|
||||||
master_size = os.path.getsize(master_path)
|
master_size = os.path.getsize(master_path)
|
||||||
new_size = os.path.getsize(new_path)
|
new_size = os.path.getsize(new_path)
|
||||||
except FileNotFoundError:
|
except FileNotFoundError:
|
||||||
|
elf_filename = result_master["vehicle"][vehicle]["elf_filename"]
|
||||||
master_path = os.path.join(master_bin_dir, elf_filename)
|
master_path = os.path.join(master_bin_dir, elf_filename)
|
||||||
new_path = os.path.join(new_bin_dir, elf_filename)
|
new_path = os.path.join(new_bin_dir, elf_filename)
|
||||||
master_size = os.path.getsize(master_path)
|
master_size = os.path.getsize(master_path)
|
||||||
@ -472,6 +736,7 @@ class SizeCompareBranches(object):
|
|||||||
|
|
||||||
identical = self.files_are_identical(master_path, new_path)
|
identical = self.files_are_identical(master_path, new_path)
|
||||||
|
|
||||||
|
board = result_master["board"]
|
||||||
ret[vehicle] = SizeCompareBranchesResult(board, vehicle, new_size - master_size, identical)
|
ret[vehicle] = SizeCompareBranchesResult(board, vehicle, new_size - master_size, identical)
|
||||||
|
|
||||||
return ret
|
return ret
|
||||||
@ -514,6 +779,11 @@ if __name__ == '__main__':
|
|||||||
action='store_true',
|
action='store_true',
|
||||||
default=False,
|
default=False,
|
||||||
help="Show result lines even if no builds were done for the board")
|
help="Show result lines even if no builds were done for the board")
|
||||||
|
parser.add_option("",
|
||||||
|
"--hide-unchanged",
|
||||||
|
action='store_true',
|
||||||
|
default=False,
|
||||||
|
help="Hide binary-size-change results for any board where output binary is unchanged")
|
||||||
parser.add_option("",
|
parser.add_option("",
|
||||||
"--board",
|
"--board",
|
||||||
action='append',
|
action='append',
|
||||||
@ -539,11 +809,26 @@ if __name__ == '__main__':
|
|||||||
action='store_true',
|
action='store_true',
|
||||||
default=False,
|
default=False,
|
||||||
help="Build all boards")
|
help="Build all boards")
|
||||||
|
parser.add_option("",
|
||||||
|
"--exclude-board-glob",
|
||||||
|
default=[],
|
||||||
|
action="append",
|
||||||
|
help="exclude any board which matches this pattern")
|
||||||
parser.add_option("",
|
parser.add_option("",
|
||||||
"--all-vehicles",
|
"--all-vehicles",
|
||||||
action='store_true',
|
action='store_true',
|
||||||
default=False,
|
default=False,
|
||||||
help="Build all vehicles")
|
help="Build all vehicles")
|
||||||
|
parser.add_option("",
|
||||||
|
"--parallel-copies",
|
||||||
|
type=int,
|
||||||
|
default=None,
|
||||||
|
help="Copy source dir this many times, build from those copies in parallel")
|
||||||
|
parser.add_option("-j",
|
||||||
|
"--jobs",
|
||||||
|
type=int,
|
||||||
|
default=None,
|
||||||
|
help="Passed to waf configure -j; number of build jobs. If running with --parallel-copies, this is divided by the number of remaining threads before being passed.") # noqa
|
||||||
cmd_opts, cmd_args = parser.parse_args()
|
cmd_opts, cmd_args = parser.parse_args()
|
||||||
|
|
||||||
vehicle = []
|
vehicle = []
|
||||||
@ -569,8 +854,12 @@ if __name__ == '__main__':
|
|||||||
run_elf_diff=(cmd_opts.elf_diff),
|
run_elf_diff=(cmd_opts.elf_diff),
|
||||||
all_vehicles=cmd_opts.all_vehicles,
|
all_vehicles=cmd_opts.all_vehicles,
|
||||||
all_boards=cmd_opts.all_boards,
|
all_boards=cmd_opts.all_boards,
|
||||||
|
exclude_board_glob=cmd_opts.exclude_board_glob,
|
||||||
use_merge_base=not cmd_opts.no_merge_base,
|
use_merge_base=not cmd_opts.no_merge_base,
|
||||||
waf_consistent_builds=not cmd_opts.no_waf_consistent_builds,
|
waf_consistent_builds=not cmd_opts.no_waf_consistent_builds,
|
||||||
show_empty=cmd_opts.show_empty,
|
show_empty=cmd_opts.show_empty,
|
||||||
|
show_unchanged=not cmd_opts.hide_unchanged,
|
||||||
|
parallel_copies=cmd_opts.parallel_copies,
|
||||||
|
jobs=cmd_opts.jobs,
|
||||||
)
|
)
|
||||||
x.run()
|
x.run()
|
||||||
|
Loading…
Reference in New Issue
Block a user