From 52468f02380a76a15541caf1e4d9bfe439c0a7ce Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Wed, 24 Jan 2024 12:16:01 -0600 Subject: [PATCH] AP_ROMFS: fix buffer null terminator Ensure buffer is properly null terminated without changing the indicated size even for uncompressed data. --- Tools/ardupilotwaf/embed.py | 10 +++++++--- libraries/AP_ROMFS/AP_ROMFS.cpp | 12 ++++++------ 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/Tools/ardupilotwaf/embed.py b/Tools/ardupilotwaf/embed.py index de7e77a483..1ca4c8f996 100755 --- a/Tools/ardupilotwaf/embed.py +++ b/Tools/ardupilotwaf/embed.py @@ -32,17 +32,21 @@ def embed_file(out, f, idx, embedded_name, uncompressed): write_encode(out, '__EXTFLASHFUNC__ static const uint8_t ap_romfs_%u[] = {' % idx) if uncompressed: - # ensure nul termination - if contents[-1] != 0: - contents += bytes([0]) + # terminate if there's not already an existing null. we don't add it to + # the contents to avoid storing the wrong length + null_terminate = 0 not in contents b = contents else: # compress it (max level, max window size, raw stream, max mem usage) z = zlib.compressobj(level=9, method=zlib.DEFLATED, wbits=-15, memLevel=9) b = z.compress(contents) b += z.flush() + # decompressed data will be null terminated at runtime, nothing to do here + null_terminate = False write_encode(out, ",".join(str(c) for c in b)) + if null_terminate: + write_encode(out, ",0") write_encode(out, '};\n\n'); return crc, len(contents) diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index a7e63dab49..67adb2313c 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -45,10 +45,10 @@ const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name) } /* - find a compressed file and uncompress it. Space for decompressed - data comes from malloc. Caller must be careful to free the resulting - data after use. The next byte after the file data is guaranteed to - be null + find a compressed file and uncompress it. Space for decompressed data comes + from malloc. Caller must be careful to free the resulting data after use. The + file data buffer is guaranteed to contain at least one null (though it may be + at buf[size]). */ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) { @@ -58,7 +58,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) } #ifdef HAL_ROMFS_UNCOMPRESSED - size = f->compressed_size; + size = f->decompressed_size; return f->contents; #else uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1); @@ -66,7 +66,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) return nullptr; } - // explicitly null terimnate the data + // explicitly null-terminate the data decompressed_data[f->decompressed_size] = 0; TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));