From 0ca37387be0c03abda28e04418a3d1f5cf52be9e Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Fri, 23 Feb 2024 16:09:37 -0600 Subject: [PATCH] AP_Filesystem: guarantee load_file() data is null-terminated Improves safety of use and clarity of users. Termination is not included in the reported size to avoid changing user behavior or misrepresenting the file contents. --- libraries/AP_Filesystem/AP_Filesystem.cpp | 4 +++- libraries/AP_Filesystem/AP_Filesystem.h | 4 +++- libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp | 6 ++++-- libraries/AP_Filesystem/AP_Filesystem_backend.cpp | 9 ++++++--- libraries/AP_Filesystem/AP_Filesystem_backend.h | 4 +++- 5 files changed, 19 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index b7642da19c..63f575bb5b 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -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) { diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h index a6ebc358dc..c2bd20e765 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.h +++ b/libraries/AP_Filesystem/AP_Filesystem.h @@ -132,7 +132,9 @@ public: 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); diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index 930b4f6268..f1aa5d69d9 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -239,8 +239,9 @@ 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) { @@ -248,6 +249,7 @@ FileData *AP_Filesystem_ROMFS::load_file(const char *filename) 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; diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp index 87fe694d9e..342eac4dbd 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp @@ -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) { @@ -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; @@ -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; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.h b/libraries/AP_Filesystem/AP_Filesystem_backend.h index 187f9c48c3..8cf0fa655a 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.h +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.h @@ -87,7 +87,9 @@ public: 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);