Skip to content

Commit

Permalink
AP_Filesystem: ROMFS: fix open race conditions
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
tpwrules committed Jan 31, 2025
1 parent c3f2b40 commit 665ddf4
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 4 deletions.
11 changes: 7 additions & 4 deletions libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<max_open_file; idx++) {
if (file[idx].data == nullptr) {
Expand All @@ -42,10 +44,6 @@ int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_
errno = ENFILE;
return -1;
}
if (file[idx].data != nullptr) {
errno = EBUSY;
return -1;
}
file[idx].data = AP_ROMFS::find_decompress(fname, file[idx].size);
if (file[idx].data == nullptr) {
errno = ENOENT;
Expand All @@ -62,6 +60,8 @@ int AP_Filesystem_ROMFS::close(int fd)
return -1;
}
AP_ROMFS::free(file[fd].data);

WITH_SEMAPHORE(record_sem); // release file record
file[fd].data = nullptr;
return 0;
}
Expand Down Expand Up @@ -142,6 +142,7 @@ int AP_Filesystem_ROMFS::mkdir(const char *pathname)

void *AP_Filesystem_ROMFS::opendir(const char *pathname)
{
WITH_SEMAPHORE(record_sem); // search for free directory record
uint8_t idx;
for (idx=0; idx<max_open_dir; idx++) {
if (dir[idx].path == nullptr) {
Expand Down Expand Up @@ -217,6 +218,8 @@ int AP_Filesystem_ROMFS::closedir(void *dirp)
return -1;
}
free(dir[idx].path);

WITH_SEMAPHORE(record_sem); // release directory record
dir[idx].path = nullptr;
return 0;
}
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_Filesystem/AP_Filesystem_ROMFS.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#if AP_FILESYSTEM_ROMFS_ENABLED

#include <AP_HAL/Semaphores.h>

#include "AP_Filesystem_backend.h"

class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 665ddf4

Please sign in to comment.