From e5efbffe5b331f1d5f2270038d64db87dc559ba5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 17 Feb 2019 12:29:14 +1100 Subject: [PATCH] waf: pad bootloader to multiple of 32 bytes this ensures that we can write a whole flash line when updating bootloader from ROMFS --- Tools/ardupilotwaf/embed.py | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/Tools/ardupilotwaf/embed.py b/Tools/ardupilotwaf/embed.py index db4da24d44..77d17bd8c4 100644 --- a/Tools/ardupilotwaf/embed.py +++ b/Tools/ardupilotwaf/embed.py @@ -12,13 +12,24 @@ import os, sys, tempfile, gzip def write_encode(out, s): out.write(s.encode()) -def embed_file(out, f, idx): +def embed_file(out, f, idx, embedded_name): '''embed one file''' try: contents = open(f,'rb').read() except Exception: print("Failed to embed %s" % f) return False + + pad = 0 + if embedded_name.endswith("bootloader.bin"): + # round size to a multiple of 32 bytes for bootloader, this ensures + # it can be flashed on a STM32H7 chip + blen = len(contents) + pad = (32 - (blen % 32)) % 32 + if pad != 0: + contents += bytes([0xff]*pad) + print("Padded %u bytes for %s" % (pad, embedded_name)) + write_encode(out, 'static const uint8_t ap_romfs_%u[] = {' % idx) # compress it @@ -45,7 +56,7 @@ def create_embedded_h(filename, files): for i in range(len(files)): (name, filename) = files[i] - if not embed_file(out, filename, i): + if not embed_file(out, filename, i, name): return False write_encode(out, '''const AP_ROMFS::embedded_file AP_ROMFS::files[] = {\n''')