mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
waf: need to crc the padded bootloaders before embedding
This commit is contained in:
parent
35149ae8b2
commit
6d25b02508
@ -17,8 +17,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
|
||||
try:
|
||||
contents = open(f,'rb').read()
|
||||
except Exception:
|
||||
print("Failed to embed %s" % f)
|
||||
return False
|
||||
raise Exception("Failed to embed %s" % f)
|
||||
|
||||
pad = 0
|
||||
if embedded_name.endswith("bootloader.bin"):
|
||||
@ -34,6 +33,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
|
||||
contents += bytes(chr(0xff))
|
||||
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)
|
||||
|
||||
compressed = tempfile.NamedTemporaryFile()
|
||||
@ -60,7 +60,7 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
|
||||
for c in b:
|
||||
write_encode(out, '%u,' % c)
|
||||
write_encode(out, '};\n\n');
|
||||
return True
|
||||
return crc
|
||||
|
||||
def crc32(bytes, crc=0):
|
||||
'''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
|
||||
files = sorted(list(set(files)))
|
||||
|
||||
crc = {}
|
||||
for i in range(len(files)):
|
||||
(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
|
||||
|
||||
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:
|
||||
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, i))
|
||||
write_encode(out, '{ "%s", sizeof(ap_romfs_%u), 0x%08x, ap_romfs_%u },\n' % (name, i, crc[filename], i))
|
||||
write_encode(out, '};\n')
|
||||
out.close()
|
||||
return True
|
||||
|
Loading…
Reference in New Issue
Block a user