diff --git a/Tools/ardupilotwaf/embed.py b/Tools/ardupilotwaf/embed.py index 1ca4c8f9966b6..836ee8254999d 100755 --- a/Tools/ardupilotwaf/embed.py +++ b/Tools/ardupilotwaf/embed.py @@ -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) diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index 67adb2313cc53..37b8a7e6b28a5 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -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) { @@ -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); @@ -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 diff --git a/libraries/AP_ROMFS/AP_ROMFS.h b/libraries/AP_ROMFS/AP_ROMFS.h index 33a7c219fb7f0..e0fecbfa1f415 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.h +++ b/libraries/AP_ROMFS/AP_ROMFS.h @@ -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); /*