Skip to content

Commit

Permalink
AP_ROMFS: remove requirement that returned buffer is null-terminated
Browse files Browse the repository at this point in the history
Also take the opportunity to clarify the function descriptions.
  • Loading branch information
tpwrules committed Feb 10, 2024
1 parent 42e5c9c commit e754938
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 21 deletions.
7 changes: 0 additions & 7 deletions Tools/ardupilotwaf/embed.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,21 +32,14 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
write_encode(out, '__EXTFLASHFUNC__ static const uint8_t ap_romfs_%u[] = {' % idx)

if uncompressed:
# 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
13 changes: 4 additions & 9 deletions libraries/AP_ROMFS/AP_ROMFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,8 @@ 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
file data buffer is guaranteed to contain at least one null (though it may be
at buf[size]).
Find the named file and return its decompressed data and size. Caller must
call AP_ROMFS::free() on the return value after use to free it.
*/
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
{
Expand All @@ -61,14 +59,11 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
size = f->decompressed_size;
return f->contents;
#else
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1);
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size);
if (!decompressed_data) {
return nullptr;
}

// explicitly null-terminate the data
decompressed_data[f->decompressed_size] = 0;

TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));
if (!d) {
::free(decompressed_data);
Expand Down Expand Up @@ -100,7 +95,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
#endif
}

// free returned data
// free decompressed file data
void AP_ROMFS::free(const uint8_t *data)
{
#ifndef HAL_ROMFS_UNCOMPRESSED
Expand Down
8 changes: 3 additions & 5 deletions libraries/AP_ROMFS/AP_ROMFS.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,11 @@

class AP_ROMFS {
public:
// find a file and de-compress, assumning gzip format. The
// decompressed data will be allocated with malloc(). You must
// call AP_ROMFS::free() on the return value after use. The next byte after
// the file data is guaranteed to be null.
// Find the named file and return its decompressed data and size. Caller
// must call AP_ROMFS::free() on the return value after use to free it.
static const uint8_t *find_decompress(const char *name, uint32_t &size);

// free returned data
// free decompressed file data
static void free(const uint8_t *data);

/*
Expand Down

0 comments on commit e754938

Please sign in to comment.