Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Filesystem: guarantee load_file() data is null-terminated #26310

Merged
merged 2 commits into from
May 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion libraries/AP_Filesystem/AP_Filesystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,9 @@ void AP_Filesystem::unmount(void)
}

/*
load a file to memory as a single chunk. Use only for small files
Load a file's contents into memory. Returned object must be `delete`d to free
the data. The data is guaranteed to be null-terminated such that it can be
treated as a string.
*/
FileData *AP_Filesystem::load_file(const char *filename)
{
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Filesystem/AP_Filesystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,9 @@ class AP_Filesystem {
AP_Filesystem_Backend::FormatStatus get_format_status() const;

/*
load a full file. Use delete to free the data
Load a file's contents into memory. Returned object must be `delete`d to
free the data. The data is guaranteed to be null-terminated such that it
can be treated as a string.
*/
FileData *load_file(const char *filename);

Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,15 +239,17 @@ bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_s
}

/*
load a full file. Use delete to free the data
we override this in ROMFS to avoid taking twice the memory
Load a file's contents into memory. Returned object must be `delete`d to free
the data. The data is guaranteed to be null-terminated such that it can be
treated as a string. Overridden in ROMFS to avoid taking twice the memory.
*/
FileData *AP_Filesystem_ROMFS::load_file(const char *filename)
{
FileData *fd = new FileData(this);
if (!fd) {
return nullptr;
}
// AP_ROMFS adds the guaranteed termination so we don't have to.
fd->data = AP_ROMFS::find_decompress(filename, fd->length);
if (fd->data == nullptr) {
delete fd;
Expand Down
9 changes: 6 additions & 3 deletions libraries/AP_Filesystem/AP_Filesystem_backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@
extern const AP_HAL::HAL& hal;

/*
load a full file. Use delete to free the data
Load a file's contents into memory. Returned object must be `delete`d to free
the data. The data is guaranteed to be null-terminated such that it can be
treated as a string.
*/
FileData *AP_Filesystem_Backend::load_file(const char *filename)
{
Expand All @@ -31,7 +33,8 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename)
if (fd == nullptr) {
return nullptr;
}
void *data = malloc(st.st_size);
// add one byte for null termination; ArduPilot's malloc will zero it.
void *data = malloc(st.st_size+1);
if (data == nullptr) {
delete fd;
return nullptr;
Expand All @@ -49,7 +52,7 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename)
return nullptr;
}
close(d);
fd->length = st.st_size;
fd->length = st.st_size; // length does not include our added termination
fd->data = (const uint8_t *)data;
return fd;
}
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Filesystem/AP_Filesystem_backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,9 @@ class AP_Filesystem_Backend {
virtual AP_Filesystem_Backend::FormatStatus get_format_status() const { return FormatStatus::NOT_STARTED; }

/*
load a full file. Use delete to free the data
Load a file's contents into memory. Returned object must be `delete`d to
free the data. The data is guaranteed to be null-terminated such that it
can be treated as a string.
*/
virtual FileData *load_file(const char *filename);

Expand Down
15 changes: 6 additions & 9 deletions libraries/AP_ROMFS/AP_ROMFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,9 @@ 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. The data is
guaranteed to be null-terminated such that it can be treated as a string.
*/
const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
{
Expand All @@ -61,20 +60,18 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size)
size = f->decompressed_size;
return f->contents;
#else
// add one byte for null termination; ArduPilot's malloc will zero it.
uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1);
if (!decompressed_data) {
return nullptr;
}

if (f->decompressed_size == 0) {
// empty file
// empty file, avoid decompression problems
size = 0;
return decompressed_data;
}

// 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 @@ -106,7 +103,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
10 changes: 5 additions & 5 deletions libraries/AP_ROMFS/AP_ROMFS.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,13 @@

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.
// The data is guaranteed to be null-terminated such that it can be
// treated as a string.
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);

// get the size of a file without decompressing
Expand Down
Loading