mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: fix flash size reporting due to crash_log
This commit is contained in:
parent
08ca708347
commit
74fa47a3bb
@ -45,10 +45,11 @@ MAX_TARGETS = 20
|
|||||||
header_text = {
|
header_text = {
|
||||||
'target': 'Target',
|
'target': 'Target',
|
||||||
'binary_path': 'Binary',
|
'binary_path': 'Binary',
|
||||||
'size_text': 'Text',
|
'size_text': 'Text (B)',
|
||||||
'size_data': 'Data',
|
'size_data': 'Data (B)',
|
||||||
'size_bss': 'BSS',
|
'size_bss': 'BSS (B)',
|
||||||
'size_total': 'Total',
|
'size_total': 'Total Flash Used (B)',
|
||||||
|
'size_free_flash': 'Free Flash (B)',
|
||||||
}
|
}
|
||||||
|
|
||||||
def text(label, text=''):
|
def text(label, text=''):
|
||||||
@ -77,7 +78,13 @@ def print_table(summary_data_list, header):
|
|||||||
header_row.append(txt)
|
header_row.append(txt)
|
||||||
max_width = len(txt)
|
max_width = len(txt)
|
||||||
for i, row_data in enumerate(summary_data_list):
|
for i, row_data in enumerate(summary_data_list):
|
||||||
txt = str(row_data.get(h, '-'))
|
data = row_data.get(h, '-')
|
||||||
|
|
||||||
|
# Output if a piece of reporting data is not applicable, example: free_flash in SITL
|
||||||
|
if data is None:
|
||||||
|
data = "Not Applicable"
|
||||||
|
|
||||||
|
txt = str(data)
|
||||||
table[i].append(txt)
|
table[i].append(txt)
|
||||||
|
|
||||||
w = len(txt)
|
w = len(txt)
|
||||||
@ -161,7 +168,18 @@ def _build_summary(bld):
|
|||||||
bld.extra_build_summary(bld, sys.modules[__name__])
|
bld.extra_build_summary(bld, sys.modules[__name__])
|
||||||
|
|
||||||
# totals=True means relying on -t flag to give us a "(TOTALS)" output
|
# totals=True means relying on -t flag to give us a "(TOTALS)" output
|
||||||
def _parse_size_output(s, totals=False):
|
def _parse_size_output(s, s_all, totals=False):
|
||||||
|
|
||||||
|
# Get the size of .crash_log to remove it from .bss reporting
|
||||||
|
crash_log_size = None
|
||||||
|
if s_all is not None:
|
||||||
|
lines = s_all.splitlines()[1:]
|
||||||
|
for line in lines:
|
||||||
|
if ".crash_log" in line:
|
||||||
|
row = line.strip().split()
|
||||||
|
crash_log_size = int(row[1])
|
||||||
|
break
|
||||||
|
|
||||||
import re
|
import re
|
||||||
pattern = re.compile("^.*TOTALS.*$")
|
pattern = re.compile("^.*TOTALS.*$")
|
||||||
lines = s.splitlines()[1:]
|
lines = s.splitlines()[1:]
|
||||||
@ -169,11 +187,25 @@ def _parse_size_output(s, totals=False):
|
|||||||
for line in lines:
|
for line in lines:
|
||||||
if pattern.match(line) or totals==False:
|
if pattern.match(line) or totals==False:
|
||||||
row = line.strip().split()
|
row = line.strip().split()
|
||||||
|
|
||||||
|
# check if crash_log wasn't found
|
||||||
|
# this will be the case for none arm boards: sitl, linux, etc.
|
||||||
|
if crash_log_size is None:
|
||||||
|
size_bss = int(row[2])
|
||||||
|
size_free_flash = None
|
||||||
|
else:
|
||||||
|
# BSS: remove the portion occupied by crash_log as the command `size binary.elf`
|
||||||
|
# reports BSS with crash_log included
|
||||||
|
size_bss = int(row[2]) - crash_log_size
|
||||||
|
size_free_flash = crash_log_size
|
||||||
|
|
||||||
l.append(dict(
|
l.append(dict(
|
||||||
size_text=int(row[0]),
|
size_text=int(row[0]),
|
||||||
size_data=int(row[1]),
|
size_data=int(row[1]),
|
||||||
size_bss=int(row[2]),
|
size_bss=size_bss,
|
||||||
size_total=int(row[3]),
|
# Total Flash Cost = Data + Text
|
||||||
|
size_total=int(row[0]) + int(row[1]),
|
||||||
|
size_free_flash=size_free_flash,
|
||||||
))
|
))
|
||||||
return l
|
return l
|
||||||
|
|
||||||
@ -191,15 +223,25 @@ def size_summary(bld, nodes):
|
|||||||
cmd = [bld.env.get_flat('SIZE')] + ["-t"] + [d['binary_path'] for d in l]
|
cmd = [bld.env.get_flat('SIZE')] + ["-t"] + [d['binary_path'] for d in l]
|
||||||
else:
|
else:
|
||||||
cmd = [bld.env.get_flat('SIZE')] + [d['binary_path'] for d in l]
|
cmd = [bld.env.get_flat('SIZE')] + [d['binary_path'] for d in l]
|
||||||
|
|
||||||
|
if bld.env.get_flat('SIZE').endswith("arm-none-eabi-size"):
|
||||||
|
cmd2 = [bld.env.get_flat('SIZE')] + ["-A"] + [d['binary_path'] for d in l]
|
||||||
|
out2 = bld.cmd_and_log(cmd2,
|
||||||
|
cwd=bld.bldnode.abspath(),
|
||||||
|
quiet=Context.BOTH,
|
||||||
|
)
|
||||||
|
else:
|
||||||
|
out2 = None
|
||||||
|
|
||||||
out = bld.cmd_and_log(
|
out = bld.cmd_and_log(
|
||||||
cmd,
|
cmd,
|
||||||
cwd=bld.bldnode.abspath(),
|
cwd=bld.bldnode.abspath(),
|
||||||
quiet=Context.BOTH,
|
quiet=Context.BOTH,
|
||||||
)
|
)
|
||||||
if bld.env.get_flat('SIZE').endswith("xtensa-esp32-elf-size"):
|
if bld.env.get_flat('SIZE').endswith("xtensa-esp32-elf-size"):
|
||||||
parsed = _parse_size_output(out,True)
|
parsed = _parse_size_output(out, out2, True)
|
||||||
else:
|
else:
|
||||||
parsed = _parse_size_output(out,False)
|
parsed = _parse_size_output(out, out2, False)
|
||||||
for i, data in enumerate(parsed):
|
for i, data in enumerate(parsed):
|
||||||
try:
|
try:
|
||||||
l[i].update(data)
|
l[i].update(data)
|
||||||
@ -242,4 +284,5 @@ def configure(cfg):
|
|||||||
'size_data',
|
'size_data',
|
||||||
'size_bss',
|
'size_bss',
|
||||||
'size_total',
|
'size_total',
|
||||||
|
'size_free_flash',
|
||||||
]
|
]
|
||||||
|
@ -32,6 +32,22 @@ def sizes_for_file(filepath):
|
|||||||
bss=int(row[2]),
|
bss=int(row[2]),
|
||||||
total=int(row[3]),
|
total=int(row[3]),
|
||||||
))
|
))
|
||||||
|
|
||||||
|
# Get the size of .crash_log to remove it from .bss reporting
|
||||||
|
cmd = "size -A %s" % (filepath,)
|
||||||
|
output = os.popen(cmd).read()
|
||||||
|
lines = output.splitlines()[1:]
|
||||||
|
for line in lines:
|
||||||
|
if ".crash_log" in line:
|
||||||
|
row = line.strip().split()
|
||||||
|
size_list[0]["crash_log"] = int(row[1])
|
||||||
|
break
|
||||||
|
|
||||||
|
# check if crash_log wasn't found and set to 0B if not found
|
||||||
|
# FIX ME : so it doesn't report Flash_Free 0B for non-ARM boards
|
||||||
|
if size_list[0].get("crash_log") is None:
|
||||||
|
size_list[0]["crash_log"] = 0
|
||||||
|
|
||||||
return size_list
|
return size_list
|
||||||
|
|
||||||
|
|
||||||
@ -49,21 +65,35 @@ def print_table(summary_data_list_second, summary_data_list_master):
|
|||||||
bvalue = summary_data_list_second[0][name].get(key)
|
bvalue = summary_data_list_second[0][name].get(key)
|
||||||
mvalue = summary_data_list_master[0][name].get(key)
|
mvalue = summary_data_list_master[0][name].get(key)
|
||||||
|
|
||||||
|
# BSS: remove the portion occupied by crash_log as the command `size binary.elf`
|
||||||
|
# reports BSS with crash_log included
|
||||||
|
if key == "bss":
|
||||||
|
mvalue = (summary_data_list_master[0][name].get("bss") -
|
||||||
|
summary_data_list_master[0][name].get("crash_log"))
|
||||||
|
bvalue = (summary_data_list_second[0][name].get("bss") -
|
||||||
|
summary_data_list_second[0][name].get("crash_log"))
|
||||||
|
|
||||||
# Total Flash Cost = Data + Text
|
# Total Flash Cost = Data + Text
|
||||||
if key == "total" and mvalue is None:
|
if key == "total":
|
||||||
mvalue = (summary_data_list_master[0][name].get("text") +
|
mvalue = (summary_data_list_master[0][name].get("text") +
|
||||||
summary_data_list_master[0][name].get("data"))
|
summary_data_list_master[0][name].get("data"))
|
||||||
|
bvalue = (summary_data_list_second[0][name].get("text") +
|
||||||
|
summary_data_list_second[0][name].get("data"))
|
||||||
diff = (bvalue - mvalue) * 100.0 / mvalue
|
diff = (bvalue - mvalue) * 100.0 / mvalue
|
||||||
signum = "+" if diff > 0.0 else ""
|
signum = "+" if diff > 0.0 else ""
|
||||||
print_diff = str(bvalue - mvalue)
|
print_diff = str(bvalue - mvalue)
|
||||||
print_diff += " (" + signum + "%0.4f%%" % diff + ")"
|
print_diff += " (" + signum + "%0.4f%%" % diff + ")"
|
||||||
col_data.append(print_diff)
|
col_data.append(print_diff)
|
||||||
|
|
||||||
|
# Append free flash space which is equivalent to crash_log's size
|
||||||
|
col_data.append(str(summary_data_list_second[0][name].get("crash_log")))
|
||||||
print_data.append(col_data)
|
print_data.append(col_data)
|
||||||
print(tabulate(print_data, headers=["Binary Name", "Text [B]", "Data [B]", "BSS (B)", "Total Flash Change [B] (%)"]))
|
print(tabulate(print_data, headers=["Binary Name", "Text [B]", "Data [B]", "BSS (B)",
|
||||||
|
"Total Flash Change [B] (%)", "Flash Free After PR (B)"]))
|
||||||
|
|
||||||
|
|
||||||
def extract_binaries_size(path):
|
def extract_binaries_size(path):
|
||||||
"""Seach and extract binary size for each binary in the given path."""
|
"""Search and extract binary size for each binary in the given path."""
|
||||||
print("Extracting binaries size on %s" % path)
|
print("Extracting binaries size on %s" % path)
|
||||||
binaries_list = []
|
binaries_list = []
|
||||||
for file in os.listdir(args.master):
|
for file in os.listdir(args.master):
|
||||||
|
Loading…
Reference in New Issue
Block a user