Browse Source

waf: need to crc the padded bootloaders before embedding

c415-sdk
bugobliterator 4 years ago committed by Andrew Tridgell
parent
commit
6d25b02508
  1. 16
      Tools/ardupilotwaf/embed.py

16
Tools/ardupilotwaf/embed.py

@ -17,8 +17,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
try: try:
contents = open(f,'rb').read() contents = open(f,'rb').read()
except Exception: except Exception:
print("Failed to embed %s" % f) raise Exception("Failed to embed %s" % f)
return False
pad = 0 pad = 0
if embedded_name.endswith("bootloader.bin"): if embedded_name.endswith("bootloader.bin"):
@ -34,6 +33,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
contents += bytes(chr(0xff)) contents += bytes(chr(0xff))
print("Padded %u bytes for %s to %u" % (pad, embedded_name, len(contents))) print("Padded %u bytes for %s to %u" % (pad, embedded_name, len(contents)))
crc = crc32(contents)
write_encode(out, 'static const uint8_t ap_romfs_%u[] = {' % idx) write_encode(out, 'static const uint8_t ap_romfs_%u[] = {' % idx)
compressed = tempfile.NamedTemporaryFile() compressed = tempfile.NamedTemporaryFile()
@ -60,7 +60,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
for c in b: for c in b:
write_encode(out, '%u,' % c) write_encode(out, '%u,' % c)
write_encode(out, '};\n\n'); write_encode(out, '};\n\n');
return True return crc
def crc32(bytes, crc=0): def crc32(bytes, crc=0):
'''crc32 equivalent to crc32_small() from AP_Math/crc.cpp''' '''crc32 equivalent to crc32_small() from AP_Math/crc.cpp'''
@ -80,10 +80,13 @@ def create_embedded_h(filename, files, uncompressed=False):
# remove duplicates and sort # remove duplicates and sort
files = sorted(list(set(files))) files = sorted(list(set(files)))
crc = {}
for i in range(len(files)): for i in range(len(files)):
(name, filename) = files[i] (name, filename) = files[i]
if not embed_file(out, filename, i, name, uncompressed): try:
crc[filename] = embed_file(out, filename, i, name, uncompressed)
except Exception as e:
print(e)
return False return False
write_encode(out, '''const AP_ROMFS::embedded_file AP_ROMFS::files[] = {\n''') write_encode(out, '''const AP_ROMFS::embedded_file AP_ROMFS::files[] = {\n''')
@ -95,8 +98,7 @@ def create_embedded_h(filename, files, uncompressed=False):
else: else:
ustr = '' ustr = ''
print("Embedding file %s:%s%s" % (name, filename, ustr)) print("Embedding file %s:%s%s" % (name, filename, ustr))
crc = crc32(bytearray(open(filename,'rb').read())) write_encode(out, '{ "%s", sizeof(ap_romfs_%u), 0x%08x, ap_romfs_%u },\n' % (name, i, crc[filename], i))
write_encode(out, '{ "%s", sizeof(ap_romfs_%u), 0x%08x, ap_romfs_%u },\n' % (name, i, crc, i))
write_encode(out, '};\n') write_encode(out, '};\n')
out.close() out.close()
return True return True

Loading…
Cancel
Save