Skip to content

Commit

Permalink
AP_ROMFS: fix buffer null terminator
Browse files Browse the repository at this point in the history
Ensure buffer is properly null terminated without changing the indicated
size even for uncompressed data.
  • Loading branch information
tpwrules authored and tridge committed Jan 25, 2024
1 parent d131931 commit 52468f0
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 9 deletions.
10 changes: 7 additions & 3 deletions Tools/ardupilotwaf/embed.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
12 changes: 6 additions & 6 deletions libraries/AP_ROMFS/AP_ROMFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand All @@ -58,15 +58,15 @@ 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);
if (!decompressed_data) {
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));
Expand Down

0 comments on commit 52468f0

Please sign in to comment.