AP_Filesystem: added interface for mount/unmount

we need to hold the FATFS semaphore when doing mount/unmount, which
means we must go via AP_Filesystem_FATFS
This commit is contained in:
Andrew Tridgell 2020-10-24 12:24:06 +11:00 committed by Peter Barker
parent 1a1a5e69dd
commit e429d578fa
5 changed files with 49 additions and 1 deletions

View File

@ -57,7 +57,7 @@ const AP_Filesystem::Backend AP_Filesystem::backends[] = {
#define MAX_FD_PER_BACKEND 256U #define MAX_FD_PER_BACKEND 256U
#define NUM_BACKENDS ARRAY_SIZE(backends) #define NUM_BACKENDS ARRAY_SIZE(backends)
#define LOCAL_BACKEND backends[0]; #define LOCAL_BACKEND backends[0]
#define BACKEND_IDX(backend) (&(backend) - &backends[0]) #define BACKEND_IDX(backend) (&(backend) - &backends[0])
/* /*
@ -215,6 +215,18 @@ bool AP_Filesystem::set_mtime(const char *filename, const uint32_t mtime_sec)
return backend.fs.set_mtime(filename, mtime_sec); return backend.fs.set_mtime(filename, mtime_sec);
} }
// if filesystem is not running then try a remount
bool AP_Filesystem::retry_mount(void)
{
return LOCAL_BACKEND.fs.retry_mount();
}
// unmount filesystem for reboot
void AP_Filesystem::unmount(void)
{
return LOCAL_BACKEND.fs.unmount();
}
namespace AP namespace AP
{ {
AP_Filesystem &FS() AP_Filesystem &FS()

View File

@ -83,6 +83,12 @@ public:
// set modification time on a file // set modification time on a file
bool set_mtime(const char *filename, const uint32_t mtime_sec); bool set_mtime(const char *filename, const uint32_t mtime_sec);
// if filesystem is not running then try a remount. Return true if fs is mounted
bool retry_mount(void);
// unmount filesystem for reboot
void unmount(void);
private: private:
struct Backend { struct Backend {
const char *prefix; const char *prefix;

View File

@ -817,6 +817,24 @@ bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_s
return f_utime(filename, (FILINFO *)&fno) == FR_OK; return f_utime(filename, (FILINFO *)&fno) == FR_OK;
} }
/*
retry mount of filesystem if needed
*/
bool AP_Filesystem_FATFS::retry_mount(void)
{
WITH_SEMAPHORE(sem);
return sdcard_retry();
}
/*
unmount filesystem for reboot
*/
void AP_Filesystem_FATFS::unmount(void)
{
WITH_SEMAPHORE(sem);
return sdcard_stop();
}
/* /*
convert POSIX errno to text with user message. convert POSIX errno to text with user message.
*/ */

View File

@ -48,4 +48,10 @@ public:
// set modification time on a file // set modification time on a file
bool set_mtime(const char *filename, const uint32_t mtime_sec) override; bool set_mtime(const char *filename, const uint32_t mtime_sec) override;
// retry mount of filesystem if needed
bool retry_mount(void) override;
// unmount filesystem for reboot
void unmount(void) override;
}; };

View File

@ -49,4 +49,10 @@ public:
// set modification time on a file // set modification time on a file
virtual bool set_mtime(const char *filename, const uint32_t mtime_sec) { return false; } virtual bool set_mtime(const char *filename, const uint32_t mtime_sec) { return false; }
// retry mount of filesystem if needed
virtual bool retry_mount(void) { return true; }
// unmount filesystem for reboot
virtual void unmount(void) {}
}; };