AP_Filesystem: disallow file operations from main thread while armed

this stops all file operations from the main thread while armed,
allowing for a 3s grace time on arming to allow for initial log
file creation
This commit is contained in:
Andrew Tridgell 2021-06-09 11:59:23 +10:00
parent 1279772d92
commit b23afc4a9e
4 changed files with 55 additions and 0 deletions

View File

@ -285,6 +285,7 @@ int AP_Filesystem_FATFS::open(const char *pathname, int flags)
FIL *fh;
int res;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT();
@ -359,6 +360,7 @@ int AP_Filesystem_FATFS::close(int fileno)
FIL *fh;
int res;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
errno = 0;
@ -389,6 +391,7 @@ int32_t AP_Filesystem_FATFS::read(int fd, void *buf, uint32_t count)
int res;
FIL *fh;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT();
@ -439,6 +442,7 @@ int32_t AP_Filesystem_FATFS::write(int fd, const void *buf, uint32_t count)
FIL *fh;
errno = 0;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT();
@ -486,6 +490,7 @@ int AP_Filesystem_FATFS::fsync(int fileno)
FIL *fh;
int res;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
errno = 0;
@ -515,6 +520,7 @@ off_t AP_Filesystem_FATFS::lseek(int fileno, off_t position, int whence)
FIL *fh;
errno = 0;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
// fileno_to_fatfs checks for fd out of bounds
@ -565,6 +571,7 @@ int AP_Filesystem_FATFS::stat(const char *name, struct stat *buf)
time_t epoch;
uint16_t mode;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT();
@ -628,6 +635,7 @@ int AP_Filesystem_FATFS::stat(const char *name, struct stat *buf)
int AP_Filesystem_FATFS::unlink(const char *pathname)
{
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
errno = 0;
@ -641,6 +649,7 @@ int AP_Filesystem_FATFS::unlink(const char *pathname)
int AP_Filesystem_FATFS::mkdir(const char *pathname)
{
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
errno = 0;
@ -664,6 +673,7 @@ struct DIR_Wrapper {
void *AP_Filesystem_FATFS::opendir(const char *pathdir)
{
FS_CHECK_ALLOWED(nullptr);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT_NULL();
@ -691,6 +701,7 @@ void *AP_Filesystem_FATFS::opendir(const char *pathdir)
struct dirent *AP_Filesystem_FATFS::readdir(void *dirp_void)
{
FS_CHECK_ALLOWED(nullptr);
WITH_SEMAPHORE(sem);
DIR *dirp = (DIR *)dirp_void;
@ -723,6 +734,7 @@ struct dirent *AP_Filesystem_FATFS::readdir(void *dirp_void)
int AP_Filesystem_FATFS::closedir(void *dirp_void)
{
DIR *dirp = (DIR *)dirp_void;
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;
@ -743,6 +755,7 @@ int AP_Filesystem_FATFS::closedir(void *dirp_void)
// return free disk space in bytes
int64_t AP_Filesystem_FATFS::disk_free(const char *path)
{
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
FATFS *fs;
@ -764,6 +777,7 @@ int64_t AP_Filesystem_FATFS::disk_free(const char *path)
// return total disk space in bytes
int64_t AP_Filesystem_FATFS::disk_space(const char *path)
{
FS_CHECK_ALLOWED(-1);
WITH_SEMAPHORE(sem);
CHECK_REMOUNT();
@ -812,6 +826,7 @@ bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_s
fno.fdate = fdate;
fno.ftime = ftime;
FS_CHECK_ALLOWED(false);
WITH_SEMAPHORE(sem);
return f_utime(filename, (FILINFO *)&fno) == FR_OK;
@ -822,6 +837,7 @@ bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_s
*/
bool AP_Filesystem_FATFS::retry_mount(void)
{
FS_CHECK_ALLOWED(false);
WITH_SEMAPHORE(sem);
return sdcard_retry();
}

View File

@ -13,8 +13,11 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_Filesystem.h"
extern const AP_HAL::HAL& hal;
/*
load a full file. Use delete to free the data
*/
@ -62,6 +65,20 @@ void AP_Filesystem_Backend::unload_file(FileData *fd)
}
}
// return true if file operations are allowed
bool AP_Filesystem_Backend::file_op_allowed(void) const
{
if (!hal.util->get_soft_armed() || !hal.scheduler->in_main_thread()) {
return true;
}
if (AP_HAL::millis() - hal.util->get_last_armed_change() < 3000) {
// allow file operations from main thread in first 3s after
// arming to allow for log file creation
return true;
}
return false;
}
/*
destructor for FileData
*/
@ -71,3 +88,4 @@ FileData::~FileData()
((AP_Filesystem_Backend *)backend)->unload_file(this);
}
}

View File

@ -78,4 +78,10 @@ public:
// unload data from load_file()
virtual void unload_file(FileData *fd);
protected:
// return true if file operations are allowed
bool file_op_allowed(void) const;
};
#define FS_CHECK_ALLOWED(retfail) do { if (!file_op_allowed()) { return retfail; } } while(0)

View File

@ -51,6 +51,7 @@ static const char *map_filename(const char *fname)
int AP_Filesystem_Posix::open(const char *fname, int flags)
{
FS_CHECK_ALLOWED(-1);
fname = map_filename(fname);
// we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage
return ::open(fname, flags | O_CLOEXEC, 0644);
@ -58,37 +59,44 @@ int AP_Filesystem_Posix::open(const char *fname, int flags)
int AP_Filesystem_Posix::close(int fd)
{
FS_CHECK_ALLOWED(-1);
return ::close(fd);
}
int32_t AP_Filesystem_Posix::read(int fd, void *buf, uint32_t count)
{
FS_CHECK_ALLOWED(-1);
return ::read(fd, buf, count);
}
int32_t AP_Filesystem_Posix::write(int fd, const void *buf, uint32_t count)
{
FS_CHECK_ALLOWED(-1);
return ::write(fd, buf, count);
}
int AP_Filesystem_Posix::fsync(int fd)
{
FS_CHECK_ALLOWED(-1);
return ::fsync(fd);
}
int32_t AP_Filesystem_Posix::lseek(int fd, int32_t offset, int seek_from)
{
FS_CHECK_ALLOWED(-1);
return ::lseek(fd, offset, seek_from);
}
int AP_Filesystem_Posix::stat(const char *pathname, struct stat *stbuf)
{
FS_CHECK_ALLOWED(-1);
pathname = map_filename(pathname);
return ::stat(pathname, stbuf);
}
int AP_Filesystem_Posix::unlink(const char *pathname)
{
FS_CHECK_ALLOWED(-1);
pathname = map_filename(pathname);
// we match the FATFS interface and use unlink
// for both files and directories
@ -101,29 +109,34 @@ int AP_Filesystem_Posix::unlink(const char *pathname)
int AP_Filesystem_Posix::mkdir(const char *pathname)
{
FS_CHECK_ALLOWED(-1);
pathname = map_filename(pathname);
return ::mkdir(pathname, 0775);
}
void *AP_Filesystem_Posix::opendir(const char *pathname)
{
FS_CHECK_ALLOWED(nullptr);
pathname = map_filename(pathname);
return (void*)::opendir(pathname);
}
struct dirent *AP_Filesystem_Posix::readdir(void *dirp)
{
FS_CHECK_ALLOWED(nullptr);
return ::readdir((DIR *)dirp);
}
int AP_Filesystem_Posix::closedir(void *dirp)
{
FS_CHECK_ALLOWED(-1);
return ::closedir((DIR *)dirp);
}
// return free disk space in bytes
int64_t AP_Filesystem_Posix::disk_free(const char *path)
{
FS_CHECK_ALLOWED(-1);
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
@ -135,6 +148,7 @@ int64_t AP_Filesystem_Posix::disk_free(const char *path)
// return total disk space in bytes
int64_t AP_Filesystem_Posix::disk_space(const char *path)
{
FS_CHECK_ALLOWED(-1);
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
@ -149,6 +163,7 @@ int64_t AP_Filesystem_Posix::disk_space(const char *path)
*/
bool AP_Filesystem_Posix::set_mtime(const char *filename, const uint32_t mtime_sec)
{
FS_CHECK_ALLOWED(false);
filename = map_filename(filename);
struct utimbuf times {};
times.actime = mtime_sec;