Browse Source

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
zr-v5.1
Andrew Tridgell 4 years ago committed by Peter Barker
parent
commit
e429d578fa
  1. 14
      libraries/AP_Filesystem/AP_Filesystem.cpp
  2. 6
      libraries/AP_Filesystem/AP_Filesystem.h
  3. 18
      libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp
  4. 6
      libraries/AP_Filesystem/AP_Filesystem_FATFS.h
  5. 6
      libraries/AP_Filesystem/AP_Filesystem_backend.h

14
libraries/AP_Filesystem/AP_Filesystem.cpp

@ -57,7 +57,7 @@ const AP_Filesystem::Backend AP_Filesystem::backends[] = { @@ -57,7 +57,7 @@ const AP_Filesystem::Backend AP_Filesystem::backends[] = {
#define MAX_FD_PER_BACKEND 256U
#define NUM_BACKENDS ARRAY_SIZE(backends)
#define LOCAL_BACKEND backends[0];
#define LOCAL_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) @@ -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);
}
// 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
{
AP_Filesystem &FS()

6
libraries/AP_Filesystem/AP_Filesystem.h

@ -83,6 +83,12 @@ public: @@ -83,6 +83,12 @@ public:
// set modification time on a file
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:
struct Backend {
const char *prefix;

18
libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp

@ -817,6 +817,24 @@ bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_s @@ -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;
}
/*
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.
*/

6
libraries/AP_Filesystem/AP_Filesystem_FATFS.h

@ -48,4 +48,10 @@ public: @@ -48,4 +48,10 @@ public:
// set modification time on a file
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;
};

6
libraries/AP_Filesystem/AP_Filesystem_backend.h

@ -49,4 +49,10 @@ public: @@ -49,4 +49,10 @@ public:
// set modification time on a file
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) {}
};

Loading…
Cancel
Save