AP_ROMFS: store size in file structure instead of compressed stream

Cleans up code.
This commit is contained in:
Thomas Watson 2023-12-30 13:53:15 -06:00 committed by Andrew Tridgell
parent d46cb3fd85
commit d13193150c
3 changed files with 24 additions and 31 deletions

View File

@ -41,13 +41,10 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
z = zlib.compressobj(level=9, method=zlib.DEFLATED, wbits=-15, memLevel=9)
b = z.compress(contents)
b += z.flush()
# append uncompressed length as little-endian bytes
l = len(contents)
b += bytes([l & 0xFF, (l >> 8) & 0xFF, (l >> 16) & 0xFF, (l >> 24) & 0xFF])
write_encode(out, ",".join(str(c) for c in b))
write_encode(out, '};\n\n');
return crc
return crc, len(contents)
def crc32(bytes, crc=0):
'''crc32 equivalent to crc32_small() from AP_Math/crc.cpp'''
@ -68,10 +65,11 @@ def create_embedded_h(filename, files, uncompressed=False):
# remove duplicates and sort
files = sorted(list(set(files)))
crc = {}
decompressed_size = {}
for i in range(len(files)):
(name, filename) = files[i]
try:
crc[filename] = embed_file(out, filename, i, name, uncompressed)
crc[filename], decompressed_size[filename] = embed_file(out, filename, i, name, uncompressed)
except Exception as e:
print(e)
return False
@ -85,7 +83,8 @@ def create_embedded_h(filename, files, uncompressed=False):
else:
ustr = ''
print("Embedding file %s:%s%s" % (name, filename, ustr))
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), %d, 0x%08x, ap_romfs_%u },\n' % (
name, i, decompressed_size[filename], crc[filename], i))
write_encode(out, '};\n')
out.close()
return True

View File

@ -34,13 +34,11 @@ const AP_ROMFS::embedded_file AP_ROMFS::files[] = {};
/*
find an embedded file
*/
const uint8_t *AP_ROMFS::find_file(const char *name, uint32_t &size, uint32_t &crc)
const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name)
{
for (uint16_t i=0; i<ARRAY_SIZE(files); i++) {
if (strcmp(name, files[i].filename) == 0) {
size = files[i].size;
crc = files[i].crc;
return files[i].contents;
return &files[i];
}
}
return nullptr;
@ -54,28 +52,22 @@ const uint8_t *AP_ROMFS::find_file(const char *name, uint32_t &size, uint32_t &c
*/
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
{
uint32_t compressed_size = 0;
uint32_t crc;
const uint8_t *compressed_data = find_file(name, compressed_size, crc);
if (!compressed_data) {
const struct embedded_file *f = find_file(name);
if (!f) {
return nullptr;
}
#ifdef HAL_ROMFS_UNCOMPRESSED
size = compressed_size;
return compressed_data;
size = f->compressed_size;
return f->contents;
#else
// last 4 bytes of compressed data are length of decompressed data
const uint8_t *p = &compressed_data[compressed_size-4];
uint32_t decompressed_size = p[0] | p[1] << 8 | p[2] << 16 | p[3] << 24;
uint8_t *decompressed_data = (uint8_t *)malloc(decompressed_size + 1);
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1);
if (!decompressed_data) {
return nullptr;
}
// explicitly null terimnate the data
decompressed_data[decompressed_size] = 0;
decompressed_data[f->decompressed_size] = 0;
TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));
if (!d) {
@ -84,10 +76,10 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
}
uzlib_uncompress_init(d, NULL, 0);
d->source = compressed_data;
d->source_limit = compressed_data + compressed_size - 4;
d->source = f->contents;
d->source_limit = f->contents + f->compressed_size;
d->dest = decompressed_data;
d->destSize = decompressed_size;
d->destSize = f->decompressed_size;
int res = uzlib_uncompress(d);
@ -98,12 +90,12 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
return nullptr;
}
if (crc32_small(0, decompressed_data, decompressed_size) != crc) {
if (crc32_small(0, decompressed_data, f->decompressed_size) != f->crc) {
::free(decompressed_data);
return nullptr;
}
size = decompressed_size;
size = f->decompressed_size;
return decompressed_data;
#endif
}

View File

@ -24,14 +24,16 @@ public:
static const char *dir_list(const char *dirname, uint16_t &ofs);
private:
// find an embedded file
static const uint8_t *find_file(const char *name, uint32_t &size, uint32_t &crc);
struct embedded_file {
const char *filename;
uint32_t size;
uint32_t compressed_size;
uint32_t decompressed_size;
uint32_t crc;
const uint8_t *contents;
};
// find an embedded file
static const AP_ROMFS::embedded_file *find_file(const char *name);
static const struct embedded_file files[];
};