Skip to content

Commit 92d7456

Browse files
committed
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.
1 parent c3f2b40 commit 92d7456

File tree

2 files changed

+12
-4
lines changed

2 files changed

+12
-4
lines changed

libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@ int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_
3232
errno = EROFS;
3333
return -1;
3434
}
35+
36+
WITH_SEMAPHORE(record_sem); // search for free file record
3537
uint8_t idx;
3638
for (idx=0; idx<max_open_file; idx++) {
3739
if (file[idx].data == nullptr) {
@@ -42,10 +44,6 @@ int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_
4244
errno = ENFILE;
4345
return -1;
4446
}
45-
if (file[idx].data != nullptr) {
46-
errno = EBUSY;
47-
return -1;
48-
}
4947
file[idx].data = AP_ROMFS::find_decompress(fname, file[idx].size);
5048
if (file[idx].data == nullptr) {
5149
errno = ENOENT;
@@ -61,6 +59,8 @@ int AP_Filesystem_ROMFS::close(int fd)
6159
errno = EBADF;
6260
return -1;
6361
}
62+
63+
WITH_SEMAPHORE(record_sem); // release file record
6464
AP_ROMFS::free(file[fd].data);
6565
file[fd].data = nullptr;
6666
return 0;
@@ -142,6 +142,7 @@ int AP_Filesystem_ROMFS::mkdir(const char *pathname)
142142

143143
void *AP_Filesystem_ROMFS::opendir(const char *pathname)
144144
{
145+
WITH_SEMAPHORE(record_sem); // search for free directory record
145146
uint8_t idx;
146147
for (idx=0; idx<max_open_dir; idx++) {
147148
if (dir[idx].path == nullptr) {
@@ -216,6 +217,8 @@ int AP_Filesystem_ROMFS::closedir(void *dirp)
216217
errno = EBADF;
217218
return -1;
218219
}
220+
221+
WITH_SEMAPHORE(record_sem); // release directory record
219222
free(dir[idx].path);
220223
dir[idx].path = nullptr;
221224
return 0;

libraries/AP_Filesystem/AP_Filesystem_ROMFS.h

+5
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@
1919

2020
#if AP_FILESYSTEM_ROMFS_ENABLED
2121

22+
#include <AP_HAL/Semaphores.h>
23+
2224
#include "AP_Filesystem_backend.h"
2325

2426
class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
@@ -56,6 +58,9 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
5658
void unload_file(FileData *fd) override;
5759

5860
private:
61+
// protect searching for free file/dir records when opening/closing
62+
HAL_Semaphore record_sem;
63+
5964
// only allow up to 4 files at a time
6065
static constexpr uint8_t max_open_file = 4;
6166
static constexpr uint8_t max_open_dir = 4;

0 commit comments

Comments
 (0)