diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp
index 353d50cc21..4488f699ad 100644
--- a/libraries/AP_Filesystem/AP_Filesystem.cpp
+++ b/libraries/AP_Filesystem/AP_Filesystem.cpp
@@ -228,6 +228,16 @@ void AP_Filesystem::unmount(void)
return LOCAL_BACKEND.fs.unmount();
}
+/*
+ load a file to memory as a single chunk. Use only for small files
+ */
+FileData *AP_Filesystem::load_file(const char *filename)
+{
+ const Backend &backend = backend_by_path(filename);
+ return backend.fs.load_file(filename);
+}
+
+
namespace AP
{
AP_Filesystem &FS()
diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h
index b148416cf1..0708a56c7e 100644
--- a/libraries/AP_Filesystem/AP_Filesystem.h
+++ b/libraries/AP_Filesystem/AP_Filesystem.h
@@ -88,6 +88,11 @@ public:
// unmount filesystem for reboot
void unmount(void);
+
+ /*
+ load a full file. Use delete to free the data
+ */
+ FileData *load_file(const char *filename);
private:
struct Backend {
diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
index 2bceb363ef..5b23b4e898 100644
--- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
+++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
@@ -212,4 +212,28 @@ bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_s
return false;
}
+/*
+ load a full file. Use delete to free the data
+ we override this 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;
+ }
+ fd->data = AP_ROMFS::find_decompress(filename, fd->length);
+ if (fd->data == nullptr) {
+ delete fd;
+ return nullptr;
+ }
+ return fd;
+}
+
+// unload data from load_file()
+void AP_Filesystem_ROMFS::unload_file(FileData *fd)
+{
+ AP_ROMFS::free(fd->data);
+}
+
#endif // HAL_HAVE_AP_ROMFS_EMBEDDED_H
diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h
index 83a316915f..fb69e23360 100644
--- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h
+++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h
@@ -43,6 +43,14 @@ public:
// set modification time on a file
bool set_mtime(const char *filename, const uint32_t mtime_sec) override;
+ /*
+ load a full file. Use delete to free the data
+ */
+ FileData *load_file(const char *filename) override;
+
+ // unload data from load_file()
+ void unload_file(FileData *fd) override;
+
private:
// only allow up to 4 files at a time
static constexpr uint8_t max_open_file = 4;
diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp
new file mode 100644
index 0000000000..e08631509e
--- /dev/null
+++ b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp
@@ -0,0 +1,73 @@
+/*
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+#include "AP_Filesystem.h"
+
+/*
+ load a full file. Use delete to free the data
+*/
+FileData *AP_Filesystem_Backend::load_file(const char *filename)
+{
+ struct stat st;
+ if (stat(filename, &st) != 0) {
+ return nullptr;
+ }
+ FileData *fd = new FileData(this);
+ if (fd == nullptr) {
+ return nullptr;
+ }
+ void *data = malloc(st.st_size);
+ if (data == nullptr) {
+ delete fd;
+ return nullptr;
+ }
+ int d = open(filename, O_RDONLY);
+ if (d == -1) {
+ free(data);
+ delete fd;
+ return nullptr;
+ }
+ if (read(d, data, st.st_size) != st.st_size) {
+ close(d);
+ free(data);
+ delete fd;
+ return nullptr;
+ }
+ close(d);
+ fd->length = st.st_size;
+ fd->data = (const uint8_t *)data;
+ return fd;
+}
+
+/*
+ unload a FileData object
+*/
+void AP_Filesystem_Backend::unload_file(FileData *fd)
+{
+ if (fd->data != nullptr) {
+ free(const_cast(fd->data));
+ fd->data = nullptr;
+ }
+}
+
+/*
+ destructor for FileData
+ */
+FileData::~FileData()
+{
+ if (backend != nullptr) {
+ ((AP_Filesystem_Backend *)backend)->unload_file(this);
+ }
+}
diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.h b/libraries/AP_Filesystem/AP_Filesystem_backend.h
index 7950472215..83ed15ee21 100644
--- a/libraries/AP_Filesystem/AP_Filesystem_backend.h
+++ b/libraries/AP_Filesystem/AP_Filesystem_backend.h
@@ -22,6 +22,21 @@
#include "AP_Filesystem_Available.h"
+// returned structure from a load_file() call
+class FileData {
+public:
+ uint32_t length;
+ const uint8_t *data;
+
+ FileData(void *_backend) :
+ backend(_backend) {}
+
+ // destructor to free data
+ ~FileData();
+private:
+ const void *backend;
+};
+
class AP_Filesystem_Backend {
public:
@@ -55,4 +70,12 @@ public:
// unmount filesystem for reboot
virtual void unmount(void) {}
+
+ /*
+ load a full file. Use delete to free the data
+ */
+ virtual FileData *load_file(const char *filename);
+
+ // unload data from load_file()
+ virtual void unload_file(FileData *fd);
};