mirror of https://github.com/ArduPilot/ardupilot
AP_ROMFS: make all decompressions null terminated
This commit is contained in:
parent
beaa069082
commit
0acb1103b0
|
@ -42,7 +42,8 @@ const uint8_t *AP_ROMFS::find_file(const char *name, uint32_t &size)
|
||||||
/*
|
/*
|
||||||
find a compressed file and uncompress it. Space for decompressed
|
find a compressed file and uncompress it. Space for decompressed
|
||||||
data comes from malloc. Caller must be careful to free the resulting
|
data comes from malloc. Caller must be careful to free the resulting
|
||||||
data after use.
|
data after use. The next byte after the file data is guaranteed to
|
||||||
|
be null
|
||||||
*/
|
*/
|
||||||
uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
|
uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
|
||||||
{
|
{
|
||||||
|
@ -56,11 +57,14 @@ uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
|
||||||
const uint8_t *p = &compressed_data[compressed_size-4];
|
const uint8_t *p = &compressed_data[compressed_size-4];
|
||||||
uint32_t decompressed_size = p[0] | p[1] << 8 | p[2] << 16 | p[3] << 24;
|
uint32_t decompressed_size = p[0] | p[1] << 8 | p[2] << 16 | p[3] << 24;
|
||||||
|
|
||||||
uint8_t *decompressed_data = (uint8_t *)malloc(decompressed_size);
|
uint8_t *decompressed_data = (uint8_t *)malloc(decompressed_size + 1);
|
||||||
if (!decompressed_data) {
|
if (!decompressed_data) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// explicitly null terimnate the data
|
||||||
|
decompressed_data[decompressed_size] = 0;
|
||||||
|
|
||||||
TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));
|
TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA));
|
||||||
if (!d) {
|
if (!d) {
|
||||||
free(decompressed_data);
|
free(decompressed_data);
|
||||||
|
|
|
@ -8,7 +8,8 @@ class AP_ROMFS {
|
||||||
public:
|
public:
|
||||||
// find a file and de-compress, assumning gzip format. The
|
// find a file and de-compress, assumning gzip format. The
|
||||||
// decompressed data will be allocated with malloc(). You must
|
// decompressed data will be allocated with malloc(). You must
|
||||||
// call free on the return value after use
|
// call free on the return value after use. The next byte after
|
||||||
|
// the file data is guaranteed to be null.
|
||||||
static uint8_t *find_decompress(const char *name, uint32_t &size);
|
static uint8_t *find_decompress(const char *name, uint32_t &size);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
Loading…
Reference in New Issue