mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
waf: fixed aligned size of bootloader in ROMFS
This commit is contained in:
parent
4561ebf0e2
commit
830cd150a2
@ -27,8 +27,12 @@ def embed_file(out, f, idx, embedded_name):
|
|||||||
blen = len(contents)
|
blen = len(contents)
|
||||||
pad = (32 - (blen % 32)) % 32
|
pad = (32 - (blen % 32)) % 32
|
||||||
if pad != 0:
|
if pad != 0:
|
||||||
|
if sys.version_info[0] >= 3:
|
||||||
contents += bytes([0xff]*pad)
|
contents += bytes([0xff]*pad)
|
||||||
print("Padded %u bytes for %s" % (pad, embedded_name))
|
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)
|
write_encode(out, 'static const uint8_t ap_romfs_%u[] = {' % idx)
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user