mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-07 04:04:07 +08:00
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.
This commit is contained in:
committed by
Peter Barker
parent
6bf29eca70
commit
63afcae8a7
@@ -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) {
|
||||
@@ -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;
|
||||
@@ -61,6 +59,8 @@ int AP_Filesystem_ROMFS::close(int fd)
|
||||
errno = EBADF;
|
||||
return -1;
|
||||
}
|
||||
|
||||
WITH_SEMAPHORE(record_sem); // release file record
|
||||
AP_ROMFS::free(file[fd].data);
|
||||
file[fd].data = nullptr;
|
||||
return 0;
|
||||
@@ -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) {
|
||||
@@ -216,6 +217,8 @@ int AP_Filesystem_ROMFS::closedir(void *dirp)
|
||||
errno = EBADF;
|
||||
return -1;
|
||||
}
|
||||
|
||||
WITH_SEMAPHORE(record_sem); // release directory record
|
||||
free(dir[idx].path);
|
||||
dir[idx].path = nullptr;
|
||||
return 0;
|
||||
|
||||
@@ -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
|
||||
@@ -56,6 +58,9 @@ public:
|
||||
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;
|
||||
|
||||
Reference in New Issue
Block a user