Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp
Views: 1798
/*1ArduPilot filesystem interface for systems using the FATFS filesystem2*/3#include "AP_Filesystem_config.h"45#if AP_FILESYSTEM_FATFS_ENABLED67#include "AP_Filesystem.h"8#include <AP_HAL/AP_HAL.h>9#include <AP_Math/AP_Math.h>10#include <stdio.h>11#include <AP_Common/time.h>1213#include <ff.h>14#include <AP_HAL_ChibiOS/sdcard.h>15#include <GCS_MAVLink/GCS.h>16#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>1718#if 019#define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)20#else21#define debug(fmt, args ...)22#endif2324extern const AP_HAL::HAL& hal;2526static bool remount_needed;2728#define FATFS_R (S_IRUSR | S_IRGRP | S_IROTH) /*< FatFs Read perms */29#define FATFS_W (S_IWUSR | S_IWGRP | S_IWOTH) /*< FatFs Write perms */30#define FATFS_X (S_IXUSR | S_IXGRP | S_IXOTH) /*< FatFs Execute perms */3132// don't write more than 4k at a time to prevent needing too much33// DMAable memory34#define MAX_IO_SIZE 40963536// use a semaphore to ensure that only one filesystem operation is37// happening at a time. A recursive semaphore is used to cope with the38// mkdir() inside sdcard_retry()39static HAL_Semaphore sem;4041typedef struct {42FIL *fh;43char *name;44} FAT_FILE;4546#define MAX_FILES 1647static FAT_FILE *file_table[MAX_FILES];4849static bool isatty_(int fileno)50{51if (fileno >= 0 && fileno <= 2) {52return true;53}54return false;55}5657/*58allocate a file descriptor59*/60static int new_file_descriptor(const char *pathname)61{62int i;63FAT_FILE *stream;64FIL *fh;6566for (i=0; i<MAX_FILES; ++i) {67if (isatty_(i)) {68continue;69}70if (file_table[i] == NULL) {71stream = (FAT_FILE *) calloc(sizeof(FAT_FILE),1);72if (stream == NULL) {73errno = ENOMEM;74return -1;75}76fh = (FIL *) calloc(sizeof(FIL),1);77if (fh == NULL) {78free(stream);79errno = ENOMEM;80return -1;81}82char *fname = (char *)malloc(strlen(pathname)+1);83if (fname == NULL) {84free(fh);85free(stream);86errno = ENOMEM;87return -1;88}89strcpy(fname, pathname);90stream->name = fname;9192file_table[i] = stream;93stream->fh = fh;94return i;95}96}97errno = ENFILE;98return -1;99}100101static FAT_FILE *fileno_to_stream(int fileno)102{103FAT_FILE *stream;104if (fileno < 0 || fileno >= MAX_FILES) {105errno = EBADF;106return nullptr;107}108109stream = file_table[fileno];110if (stream == NULL) {111errno = EBADF;112return nullptr;113}114return stream;115}116117static int free_file_descriptor(int fileno)118{119FAT_FILE *stream;120FIL *fh;121122if (isatty_( fileno )) {123errno = EBADF;124return -1;125}126127// checks if fileno out of bounds128stream = fileno_to_stream(fileno);129if (stream == nullptr) {130return -1;131}132133fh = stream->fh;134135if (fh != NULL) {136free(fh);137}138139free(stream->name);140stream->name = NULL;141142file_table[fileno] = NULL;143free(stream);144return fileno;145}146147static FIL *fileno_to_fatfs(int fileno)148{149FAT_FILE *stream;150FIL *fh;151152if (isatty_(fileno)) {153errno = EBADF;154return nullptr;155}156157// checks if fileno out of bounds158stream = fileno_to_stream(fileno);159if (stream == nullptr) {160return nullptr;161}162163fh = stream->fh;164if (fh == NULL) {165errno = EBADF;166return nullptr;167}168return fh;169}170171static int fatfs_to_errno(FRESULT Result)172{173switch (Result) {174case FR_OK: /* FatFS (0) Succeeded */175return 0; /* POSIX OK */176case FR_DISK_ERR: /* FatFS (1) A hard error occurred in the low level disk I/O layer */177return EIO; /* POSIX Input/output error (POSIX.1) */178179case FR_INT_ERR: /* FatFS (2) Assertion failed */180return EPERM; /* POSIX Operation not permitted (POSIX.1) */181182case FR_NOT_READY: /* FatFS (3) The physical drive cannot work */183return EBUSY; /* POSIX Device or resource busy (POSIX.1) */184185case FR_NO_FILE: /* FatFS (4) Could not find the file */186return ENOENT; /* POSIX No such file or directory (POSIX.1) */187188case FR_NO_PATH: /* FatFS (5) Could not find the path */189return ENOENT; /* POSIX No such file or directory (POSIX.1) */190191case FR_INVALID_NAME: /* FatFS (6) The path name format is invalid */192return EINVAL; /* POSIX Invalid argument (POSIX.1) */193194case FR_DENIED: /* FatFS (7) Access denied due to prohibited access or directory full */195return EACCES; /* POSIX Permission denied (POSIX.1) */196197case FR_EXIST: /* file exists */198return EEXIST; /* file exists */199200case FR_INVALID_OBJECT: /* FatFS (9) The file/directory object is invalid */201return EINVAL; /* POSIX Invalid argument (POSIX.1) */202203case FR_WRITE_PROTECTED: /* FatFS (10) The physical drive is write protected */204return EROFS; /* POSIX Read-only filesystem (POSIX.1) */205206case FR_INVALID_DRIVE: /* FatFS (11) The logical drive number is invalid */207return ENXIO; /* POSIX No such device or address (POSIX.1) */208209case FR_NOT_ENABLED: /* FatFS (12) The volume has no work area */210return ENOSPC; /* POSIX No space left on device (POSIX.1) */211212case FR_NO_FILESYSTEM: /* FatFS (13) There is no valid FAT volume */213return ENXIO; /* POSIX No such device or address (POSIX.1) */214215case FR_MKFS_ABORTED: /* FatFS (14) The f_mkfs() aborted due to any parameter error */216return EINVAL; /* POSIX Invalid argument (POSIX.1) */217218case FR_TIMEOUT: /* FatFS (15) Could not get a grant to access the volume within defined period */219return EBUSY; /* POSIX Device or resource busy (POSIX.1) */220221case FR_LOCKED: /* FatFS (16) The operation is rejected according to the file sharing policy */222return EBUSY; /* POSIX Device or resource busy (POSIX.1) */223224225case FR_NOT_ENOUGH_CORE: /* FatFS (17) LFN working buffer could not be allocated */226return ENOMEM; /* POSIX Not enough space (POSIX.1) */227228case FR_TOO_MANY_OPEN_FILES:/* FatFS (18) Number of open files > _FS_SHARE */229return EMFILE; /* POSIX Too many open files (POSIX.1) */230231case FR_INVALID_PARAMETER:/* FatFS (19) Given parameter is invalid */232return EINVAL; /* POSIX Invalid argument (POSIX.1) */233234}235return EBADMSG; /* POSIX Bad message (POSIX.1) */236}237238// check for a remount and return -1 if it fails239#define CHECK_REMOUNT() do { if (remount_needed && !remount_file_system()) { errno = EIO; return -1; }} while (0)240#define CHECK_REMOUNT_NULL() do { if (remount_needed && !remount_file_system()) { errno = EIO; return NULL; }} while (0)241242// we allow for IO retries if either not armed or not in main thread243#define RETRY_ALLOWED() (!hal.scheduler->in_main_thread() || !hal.util->get_soft_armed())244245/*246try to remount the file system on disk error247*/248static bool remount_file_system(void)249{250EXPECT_DELAY_MS(3000);251if (!remount_needed) {252sdcard_stop();253}254if (!sdcard_retry()) {255remount_needed = true;256return false;257}258remount_needed = false;259for (uint16_t i=0; i<MAX_FILES; i++) {260FAT_FILE *f = file_table[i];261if (!f) {262continue;263}264FIL *fh = f->fh;265FSIZE_t offset = fh->fptr;266uint8_t flags = fh->flag & (FA_READ | FA_WRITE);267268memset(fh, 0, sizeof(*fh));269if (flags & FA_WRITE) {270// the file may not have been created yet on the sdcard271flags |= FA_OPEN_ALWAYS;272}273FRESULT res = f_open(fh, f->name, flags);274debug("reopen %s flags=0x%x ofs=%u -> %d\n", f->name, unsigned(flags), unsigned(offset), int(res));275if (res == FR_OK) {276f_lseek(fh, offset);277}278}279return true;280}281282int AP_Filesystem_FATFS::open(const char *pathname, int flags, bool allow_absolute_path)283{284int fileno;285int fatfs_modes;286FAT_FILE *stream;287FIL *fh;288int res;289290FS_CHECK_ALLOWED(-1);291WITH_SEMAPHORE(sem);292293CHECK_REMOUNT();294295errno = 0;296debug("Open %s 0x%x", pathname, flags);297298if ((flags & O_ACCMODE) == O_RDWR) {299fatfs_modes = FA_READ | FA_WRITE;300} else if ((flags & O_ACCMODE) == O_RDONLY) {301fatfs_modes = FA_READ;302} else {303fatfs_modes = FA_WRITE;304}305306if (flags & O_CREAT) {307if (flags & O_TRUNC) {308fatfs_modes |= FA_CREATE_ALWAYS;309} else {310fatfs_modes |= FA_OPEN_ALWAYS;311}312}313314fileno = new_file_descriptor(pathname);315316// checks if fileno out of bounds317stream = fileno_to_stream(fileno);318if (stream == nullptr) {319free_file_descriptor(fileno);320return -1;321}322323// fileno_to_fatfs checks for fileno out of bounds324fh = fileno_to_fatfs(fileno);325if (fh == nullptr) {326free_file_descriptor(fileno);327errno = EBADF;328return -1;329}330res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));331if (res == FR_DISK_ERR && RETRY_ALLOWED()) {332// one retry on disk error333hal.scheduler->delay(100);334if (remount_file_system()) {335res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));336}337}338if (res != FR_OK) {339errno = fatfs_to_errno((FRESULT)res);340free_file_descriptor(fileno);341return -1;342}343if (flags & O_APPEND) {344/// Seek to end of the file345res = f_lseek(fh, f_size(fh));346if (res != FR_OK) {347errno = fatfs_to_errno((FRESULT)res);348f_close(fh);349free_file_descriptor(fileno);350return -1;351}352}353354debug("Open %s -> %d", pathname, fileno);355356return fileno;357}358359int AP_Filesystem_FATFS::close(int fileno)360{361FAT_FILE *stream;362FIL *fh;363int res;364365FS_CHECK_ALLOWED(-1);366WITH_SEMAPHORE(sem);367368errno = 0;369370// checks if fileno out of bounds371stream = fileno_to_stream(fileno);372if (stream == nullptr) {373return -1;374}375376// fileno_to_fatfs checks for fileno out of bounds377fh = fileno_to_fatfs(fileno);378if (fh == nullptr) {379return -1;380}381res = f_close(fh);382free_file_descriptor(fileno);383if (res != FR_OK) {384errno = fatfs_to_errno((FRESULT)res);385return -1;386}387return 0;388}389390int32_t AP_Filesystem_FATFS::read(int fd, void *buf, uint32_t count)391{392UINT bytes = count;393int res;394FIL *fh;395396FS_CHECK_ALLOWED(-1);397WITH_SEMAPHORE(sem);398399CHECK_REMOUNT();400401if (count > 0) {402*(char *) buf = 0;403}404405errno = 0;406407// fileno_to_fatfs checks for fd out of bounds408fh = fileno_to_fatfs(fd);409if (fh == nullptr) {410errno = EBADF;411return -1;412}413414UINT total = 0;415do {416UINT size = 0;417UINT n = bytes;418if (!mem_is_dma_safe(buf, count, true)) {419n = MIN(bytes, MAX_IO_SIZE);420}421res = f_read(fh, (void *)buf, n, &size);422if (res != FR_OK) {423errno = fatfs_to_errno((FRESULT)res);424return -1;425}426if (size == 0) {427break;428}429if (size > n) {430errno = EIO;431return -1;432}433total += size;434buf = (void *)(((uint8_t *)buf)+size);435bytes -= size;436if (size < n) {437break;438}439} while (bytes > 0);440return (ssize_t)total;441}442443int32_t AP_Filesystem_FATFS::write(int fd, const void *buf, uint32_t count)444{445UINT bytes = count;446FRESULT res;447FIL *fh;448errno = 0;449450FS_CHECK_ALLOWED(-1);451WITH_SEMAPHORE(sem);452453CHECK_REMOUNT();454455// fileno_to_fatfs checks for fd out of bounds456fh = fileno_to_fatfs(fd);457if (fh == nullptr) {458errno = EBADF;459return -1;460}461462UINT total = 0;463do {464UINT n = bytes;465if (!mem_is_dma_safe(buf, count, true)) {466n = MIN(bytes, MAX_IO_SIZE);467}468UINT size = 0;469res = f_write(fh, buf, n, &size);470if (res == FR_DISK_ERR && RETRY_ALLOWED()) {471// one retry on disk error472hal.scheduler->delay(100);473if (remount_file_system()) {474res = f_write(fh, buf, n, &size);475}476}477if (size > n || size == 0) {478errno = EIO;479return -1;480}481if (res != FR_OK || size > n) {482errno = fatfs_to_errno(res);483return -1;484}485total += size;486buf = (void *)(((uint8_t *)buf)+size);487bytes -= size;488if (size < n) {489break;490}491} while (bytes > 0);492return (ssize_t)total;493}494495int AP_Filesystem_FATFS::fsync(int fileno)496{497FAT_FILE *stream;498FIL *fh;499int res;500501FS_CHECK_ALLOWED(-1);502WITH_SEMAPHORE(sem);503504errno = 0;505506// checks if fileno out of bounds507stream = fileno_to_stream(fileno);508if (stream == nullptr) {509return -1;510}511512// fileno_to_fatfs checks for fileno out of bounds513fh = fileno_to_fatfs(fileno);514if (fh == nullptr) {515return -1;516}517res = f_sync(fh);518if (res != FR_OK) {519errno = fatfs_to_errno((FRESULT)res);520return -1;521}522return 0;523}524525off_t AP_Filesystem_FATFS::lseek(int fileno, off_t position, int whence)526{527FRESULT res;528FIL *fh;529errno = 0;530531FS_CHECK_ALLOWED(-1);532WITH_SEMAPHORE(sem);533534// fileno_to_fatfs checks for fd out of bounds535fh = fileno_to_fatfs(fileno);536if (fh == nullptr) {537errno = EMFILE;538return -1;539}540if (isatty_(fileno)) {541return -1;542}543544if (whence == SEEK_END) {545position += f_size(fh);546} else if (whence==SEEK_CUR) {547position += fh->fptr;548}549550res = f_lseek(fh, position);551if (res) {552errno = fatfs_to_errno(res);553return -1;554}555return fh->fptr;556}557558static time_t fat_time_to_unix(uint16_t date, uint16_t time)559{560struct tm tp;561time_t unix;562563memset(&tp, 0, sizeof(struct tm));564565tp.tm_sec = (time << 1) & 0x3e; // 2 second resolution566tp.tm_min = ((time >> 5) & 0x3f);567tp.tm_hour = ((time >> 11) & 0x1f);568tp.tm_mday = (date & 0x1f);569tp.tm_mon = ((date >> 5) & 0x0f) - 1;570tp.tm_year = ((date >> 9) & 0x7f) + 80;571unix = ap_mktime(&tp);572return unix;573}574575int AP_Filesystem_FATFS::stat(const char *name, struct stat *buf)576{577FILINFO info;578int res;579time_t epoch;580uint16_t mode;581582FS_CHECK_ALLOWED(-1);583WITH_SEMAPHORE(sem);584585CHECK_REMOUNT();586587errno = 0;588589// f_stat does not handle / or . as root directory590if (strcmp(name,"/") == 0 || strcmp(name,".") == 0) {591buf->st_atime = 0;592buf->st_mtime = 0;593buf->st_ctime = 0;594buf->st_uid= 0;595buf->st_gid= 0;596buf->st_size = 0;597buf->st_mode = S_IFDIR;598return 0;599}600601res = f_stat(name, &info);602if (res == FR_DISK_ERR && RETRY_ALLOWED()) {603// one retry on disk error604if (remount_file_system()) {605res = f_stat(name, &info);606}607}608if (res != FR_OK) {609errno = fatfs_to_errno((FRESULT)res);610return -1;611}612613buf->st_size = info.fsize;614epoch = fat_time_to_unix(info.fdate, info.ftime);615buf->st_atime = epoch; // Access time616buf->st_mtime = epoch; // Modification time617buf->st_ctime = epoch; // Creation time618619// We only handle read only case620mode = (FATFS_R | FATFS_X);621if (!(info.fattrib & AM_RDO)) {622mode |= (FATFS_W); // enable write if NOT read only623}624625if (info.fattrib & AM_SYS) {626buf->st_uid= 0;627buf->st_gid= 0;628}629{630buf->st_uid=1000;631buf->st_gid=1000;632}633634if (info.fattrib & AM_DIR) {635mode |= S_IFDIR;636} else {637mode |= S_IFREG;638}639buf->st_mode = mode;640641return 0;642}643644int AP_Filesystem_FATFS::unlink(const char *pathname)645{646FS_CHECK_ALLOWED(-1);647WITH_SEMAPHORE(sem);648649errno = 0;650int res = f_unlink(pathname);651if (res != FR_OK) {652errno = fatfs_to_errno((FRESULT)res);653return -1;654}655return 0;656}657658int AP_Filesystem_FATFS::mkdir(const char *pathname)659{660FS_CHECK_ALLOWED(-1);661WITH_SEMAPHORE(sem);662663errno = 0;664665int res = f_mkdir(pathname);666if (res != FR_OK) {667errno = fatfs_to_errno((FRESULT)res);668return -1;669}670671return 0;672}673674int AP_Filesystem_FATFS::rename(const char *oldpath, const char *newpath)675{676FS_CHECK_ALLOWED(-1);677WITH_SEMAPHORE(sem);678679errno = 0;680681int res = f_rename(oldpath, newpath);682if (res != FR_OK) {683errno = fatfs_to_errno((FRESULT)res);684return -1;685}686687return 0;688}689690/*691wrapper structure to associate a dirent with a DIR692*/693struct DIR_Wrapper {694DIR d; // must be first structure element695struct dirent de;696};697698void *AP_Filesystem_FATFS::opendir(const char *pathdir)699{700FS_CHECK_ALLOWED(nullptr);701WITH_SEMAPHORE(sem);702703CHECK_REMOUNT_NULL();704705debug("Opendir %s", pathdir);706struct DIR_Wrapper *ret = NEW_NOTHROW DIR_Wrapper;707if (!ret) {708return nullptr;709}710int res = f_opendir(&ret->d, pathdir);711if (res == FR_DISK_ERR && RETRY_ALLOWED()) {712// one retry on disk error713if (remount_file_system()) {714res = f_opendir(&ret->d, pathdir);715}716}717if (res != FR_OK) {718errno = fatfs_to_errno((FRESULT)res);719delete ret;720return nullptr;721}722debug("Opendir %s -> %p", pathdir, ret);723return &ret->d;724}725726struct dirent *AP_Filesystem_FATFS::readdir(void *dirp_void)727{728FS_CHECK_ALLOWED(nullptr);729WITH_SEMAPHORE(sem);730DIR *dirp = (DIR *)dirp_void;731732struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;733if (!d) {734errno = EINVAL;735return nullptr;736}737FILINFO fno;738int len;739int res;740741d->de.d_name[0] = 0;742res = f_readdir(dirp, &fno);743if (res != FR_OK || fno.fname[0] == 0) {744errno = fatfs_to_errno((FRESULT)res);745return nullptr;746}747len = strlen(fno.fname);748strncpy_noterm(d->de.d_name,fno.fname,len);749d->de.d_name[len] = 0;750if (fno.fattrib & AM_DIR) {751d->de.d_type = DT_DIR;752} else {753d->de.d_type = DT_REG;754}755return &d->de;756}757758int AP_Filesystem_FATFS::closedir(void *dirp_void)759{760DIR *dirp = (DIR *)dirp_void;761FS_CHECK_ALLOWED(-1);762WITH_SEMAPHORE(sem);763764struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;765if (!d) {766errno = EINVAL;767return -1;768}769int res = f_closedir (dirp);770delete d;771if (res != FR_OK) {772errno = fatfs_to_errno((FRESULT)res);773return -1;774}775debug("closedir");776return 0;777}778779// return free disk space in bytes780int64_t AP_Filesystem_FATFS::disk_free(const char *path)781{782FS_CHECK_ALLOWED(-1);783WITH_SEMAPHORE(sem);784785FATFS *fs;786DWORD fre_clust, fre_sect;787788CHECK_REMOUNT();789790/* Get volume information and free clusters of drive 1 */791FRESULT res = f_getfree("/", &fre_clust, &fs);792if (res) {793return res;794}795796/* Get total sectors and free sectors */797fre_sect = fre_clust * fs->csize;798return (int64_t)(fre_sect)*512;799}800801// return total disk space in bytes802int64_t AP_Filesystem_FATFS::disk_space(const char *path)803{804FS_CHECK_ALLOWED(-1);805WITH_SEMAPHORE(sem);806807CHECK_REMOUNT();808809FATFS *fs;810DWORD fre_clust, tot_sect;811812/* Get volume information and free clusters of drive 1 */813FRESULT res = f_getfree("/", &fre_clust, &fs);814if (res) {815return -1;816}817818/* Get total sectors and free sectors */819tot_sect = (fs->n_fatent - 2) * fs->csize;820return (int64_t)(tot_sect)*512;821}822823/*824convert unix time_t to FATFS timestamp825*/826static void unix_time_to_fat(time_t epoch, uint16_t &date, uint16_t &time)827{828struct tm tmd {};829struct tm *t = gmtime_r((time_t *)&epoch, &tmd);830831/* Pack date and time into a uint32_t variable */832date = ((uint16_t)(t->tm_year - 80) << 9)833| (((uint16_t)t->tm_mon+1) << 5)834| (((uint16_t)t->tm_mday));835836time = ((uint16_t)t->tm_hour << 11)837| ((uint16_t)t->tm_min << 5)838| ((uint16_t)t->tm_sec >> 1);839}840841/*842set mtime on a file843*/844bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_sec)845{846FILINFO fno;847uint16_t fdate, ftime;848849unix_time_to_fat(mtime_sec, fdate, ftime);850851fno.fdate = fdate;852fno.ftime = ftime;853854FS_CHECK_ALLOWED(false);855WITH_SEMAPHORE(sem);856857return f_utime(filename, (FILINFO *)&fno) == FR_OK;858}859860/*861retry mount of filesystem if needed862*/863bool AP_Filesystem_FATFS::retry_mount(void)864{865FS_CHECK_ALLOWED(false);866WITH_SEMAPHORE(sem);867return sdcard_retry();868}869870/*871unmount filesystem for reboot872*/873void AP_Filesystem_FATFS::unmount(void)874{875WITH_SEMAPHORE(sem);876return sdcard_stop();877}878879/*880format sdcard881*/882bool AP_Filesystem_FATFS::format(void)883{884#if FF_USE_MKFS885WITH_SEMAPHORE(sem);886hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FATFS::format_handler, void));887// the format is handled asynchronously, we inform user of success888// via a text message. format_status can be polled for progress889format_status = FormatStatus::PENDING;890return true;891#else892return false;893#endif894}895896/*897format sdcard898*/899void AP_Filesystem_FATFS::format_handler(void)900{901#if FF_USE_MKFS902if (format_status != FormatStatus::PENDING) {903return;904}905WITH_SEMAPHORE(sem);906format_status = FormatStatus::IN_PROGRESS;907GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting SDCard");908uint8_t *buf = (uint8_t *)hal.util->malloc_type(FF_MAX_SS, AP_HAL::Util::MEM_DMA_SAFE);909if (buf == nullptr) {910return;911}912// format first disk913auto ret = f_mkfs("0:", 0, buf, FF_MAX_SS);914hal.util->free_type(buf, FF_MAX_SS, AP_HAL::Util::MEM_DMA_SAFE);915if (ret == FR_OK) {916format_status = FormatStatus::SUCCESS;917GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format: OK");918} else {919format_status = FormatStatus::FAILURE;920GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format: Failed (%d)", int(ret));921}922sdcard_stop();923sdcard_retry();924#endif925}926927// returns true if we are currently formatting the SD card:928AP_Filesystem_Backend::FormatStatus AP_Filesystem_FATFS::get_format_status(void) const929{930// note that format_handler holds sem, so we can't take it here.931return format_status;932}933934/*935convert POSIX errno to text with user message.936*/937char *strerror(int errnum)938{939#define SWITCH_ERROR(errno) case errno: return const_cast<char *>(#errno); break940switch (errnum) {941SWITCH_ERROR(EPERM);942SWITCH_ERROR(ENOENT);943SWITCH_ERROR(ESRCH);944SWITCH_ERROR(EINTR);945SWITCH_ERROR(EIO);946SWITCH_ERROR(ENXIO);947SWITCH_ERROR(E2BIG);948SWITCH_ERROR(ENOEXEC);949SWITCH_ERROR(EBADF);950SWITCH_ERROR(ECHILD);951SWITCH_ERROR(EAGAIN);952SWITCH_ERROR(ENOMEM);953SWITCH_ERROR(EACCES);954SWITCH_ERROR(EFAULT);955#ifdef ENOTBLK956SWITCH_ERROR(ENOTBLK);957#endif // ENOTBLK958SWITCH_ERROR(EBUSY);959SWITCH_ERROR(EEXIST);960SWITCH_ERROR(EXDEV);961SWITCH_ERROR(ENODEV);962SWITCH_ERROR(ENOTDIR);963SWITCH_ERROR(EISDIR);964SWITCH_ERROR(EINVAL);965SWITCH_ERROR(ENFILE);966SWITCH_ERROR(EMFILE);967SWITCH_ERROR(ENOTTY);968SWITCH_ERROR(ETXTBSY);969SWITCH_ERROR(EFBIG);970SWITCH_ERROR(ENOSPC);971SWITCH_ERROR(ESPIPE);972SWITCH_ERROR(EROFS);973SWITCH_ERROR(EMLINK);974SWITCH_ERROR(EPIPE);975SWITCH_ERROR(EDOM);976SWITCH_ERROR(ERANGE);977SWITCH_ERROR(EBADMSG);978}979980#undef SWITCH_ERROR981982return NULL;983}984985#endif // AP_FILESYSTEM_FATFS_ENABLED986987988