From 830cd150a29ffbc839139991748cf56fc17a423f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 23 Dec 2019 17:29:18 +1100 Subject: [PATCH] waf: fixed aligned size of bootloader in ROMFS --- Tools/ardupilotwaf/embed.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Tools/ardupilotwaf/embed.py b/Tools/ardupilotwaf/embed.py index 77d17bd8c4..b4305f5ecd 100644 --- a/Tools/ardupilotwaf/embed.py +++ b/Tools/ardupilotwaf/embed.py @@ -27,8 +27,12 @@ def embed_file(out, f, idx, embedded_name): blen = len(contents) pad = (32 - (blen % 32)) % 32 if pad != 0: - contents += bytes([0xff]*pad) - print("Padded %u bytes for %s" % (pad, embedded_name)) + if sys.version_info[0] >= 3: + contents += bytes([0xff]*pad) + else: + for i in range(pad): + contents += bytes(chr(0xff)) + print("Padded %u bytes for %s to %u" % (pad, embedded_name, len(contents))) write_encode(out, 'static const uint8_t ap_romfs_%u[] = {' % idx)