From 92d7456263125d71da2b6aa332de99cb98489c9d Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 30 Jan 2025 19:34:58 -0600 Subject: [PATCH] AP_Filesystem: ROMFS: fix open race conditions Lua opens scripts to load them into memory, then the logger opens them after to stream them into the dataflash log. When loading multiple large Lua scripts from ROMFS, decompression takes a significant amount of time. This creates the opportunity for the Lua interpreter and logging threads to both be inside `AP_Filesystem_ROMFS::open()` decompressing a file. If this happens, the function can return the same `fd` for two different calls as the `fd` is chosen before decompression starts, but only marked as being used after that finishes. The read pointers then stomp on each other, so Lua loads garbled scripts (usually resulting in a syntax error) and the logger dumps garbled data. Fix the issue by locking before searching for a free record (or marking a record as free). Apply the same fix to directories as well. This doesn't protect against using the same `fd`/`dirp` from multiple threads, but that behavior is to be discouraged anyway and is not the root cause here. --- libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp | 11 +++++++---- libraries/AP_Filesystem/AP_Filesystem_ROMFS.h | 5 +++++ 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index f481d872558e5..d4eca8812fb82 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -32,6 +32,8 @@ int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_ errno = EROFS; return -1; } + + WITH_SEMAPHORE(record_sem); // search for free file record uint8_t idx; for (idx=0; idx + #include "AP_Filesystem_backend.h" class AP_Filesystem_ROMFS : public AP_Filesystem_Backend @@ -56,6 +58,9 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend void unload_file(FileData *fd) override; private: + // protect searching for free file/dir records when opening/closing + HAL_Semaphore record_sem; + // only allow up to 4 files at a time static constexpr uint8_t max_open_file = 4; static constexpr uint8_t max_open_dir = 4;