CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp
Views: 1798
1
/*
2
ArduPilot filesystem interface for systems using the FATFS filesystem
3
*/
4
#include "AP_Filesystem_config.h"
5
6
#if AP_FILESYSTEM_FATFS_ENABLED
7
8
#include "AP_Filesystem.h"
9
#include <AP_HAL/AP_HAL.h>
10
#include <AP_Math/AP_Math.h>
11
#include <stdio.h>
12
#include <AP_Common/time.h>
13
14
#include <ff.h>
15
#include <AP_HAL_ChibiOS/sdcard.h>
16
#include <GCS_MAVLink/GCS.h>
17
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
18
19
#if 0
20
#define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
21
#else
22
#define debug(fmt, args ...)
23
#endif
24
25
extern const AP_HAL::HAL& hal;
26
27
static bool remount_needed;
28
29
#define FATFS_R (S_IRUSR | S_IRGRP | S_IROTH) /*< FatFs Read perms */
30
#define FATFS_W (S_IWUSR | S_IWGRP | S_IWOTH) /*< FatFs Write perms */
31
#define FATFS_X (S_IXUSR | S_IXGRP | S_IXOTH) /*< FatFs Execute perms */
32
33
// don't write more than 4k at a time to prevent needing too much
34
// DMAable memory
35
#define MAX_IO_SIZE 4096
36
37
// use a semaphore to ensure that only one filesystem operation is
38
// happening at a time. A recursive semaphore is used to cope with the
39
// mkdir() inside sdcard_retry()
40
static HAL_Semaphore sem;
41
42
typedef struct {
43
FIL *fh;
44
char *name;
45
} FAT_FILE;
46
47
#define MAX_FILES 16
48
static FAT_FILE *file_table[MAX_FILES];
49
50
static bool isatty_(int fileno)
51
{
52
if (fileno >= 0 && fileno <= 2) {
53
return true;
54
}
55
return false;
56
}
57
58
/*
59
allocate a file descriptor
60
*/
61
static int new_file_descriptor(const char *pathname)
62
{
63
int i;
64
FAT_FILE *stream;
65
FIL *fh;
66
67
for (i=0; i<MAX_FILES; ++i) {
68
if (isatty_(i)) {
69
continue;
70
}
71
if (file_table[i] == NULL) {
72
stream = (FAT_FILE *) calloc(sizeof(FAT_FILE),1);
73
if (stream == NULL) {
74
errno = ENOMEM;
75
return -1;
76
}
77
fh = (FIL *) calloc(sizeof(FIL),1);
78
if (fh == NULL) {
79
free(stream);
80
errno = ENOMEM;
81
return -1;
82
}
83
char *fname = (char *)malloc(strlen(pathname)+1);
84
if (fname == NULL) {
85
free(fh);
86
free(stream);
87
errno = ENOMEM;
88
return -1;
89
}
90
strcpy(fname, pathname);
91
stream->name = fname;
92
93
file_table[i] = stream;
94
stream->fh = fh;
95
return i;
96
}
97
}
98
errno = ENFILE;
99
return -1;
100
}
101
102
static FAT_FILE *fileno_to_stream(int fileno)
103
{
104
FAT_FILE *stream;
105
if (fileno < 0 || fileno >= MAX_FILES) {
106
errno = EBADF;
107
return nullptr;
108
}
109
110
stream = file_table[fileno];
111
if (stream == NULL) {
112
errno = EBADF;
113
return nullptr;
114
}
115
return stream;
116
}
117
118
static int free_file_descriptor(int fileno)
119
{
120
FAT_FILE *stream;
121
FIL *fh;
122
123
if (isatty_( fileno )) {
124
errno = EBADF;
125
return -1;
126
}
127
128
// checks if fileno out of bounds
129
stream = fileno_to_stream(fileno);
130
if (stream == nullptr) {
131
return -1;
132
}
133
134
fh = stream->fh;
135
136
if (fh != NULL) {
137
free(fh);
138
}
139
140
free(stream->name);
141
stream->name = NULL;
142
143
file_table[fileno] = NULL;
144
free(stream);
145
return fileno;
146
}
147
148
static FIL *fileno_to_fatfs(int fileno)
149
{
150
FAT_FILE *stream;
151
FIL *fh;
152
153
if (isatty_(fileno)) {
154
errno = EBADF;
155
return nullptr;
156
}
157
158
// checks if fileno out of bounds
159
stream = fileno_to_stream(fileno);
160
if (stream == nullptr) {
161
return nullptr;
162
}
163
164
fh = stream->fh;
165
if (fh == NULL) {
166
errno = EBADF;
167
return nullptr;
168
}
169
return fh;
170
}
171
172
static int fatfs_to_errno(FRESULT Result)
173
{
174
switch (Result) {
175
case FR_OK: /* FatFS (0) Succeeded */
176
return 0; /* POSIX OK */
177
case FR_DISK_ERR: /* FatFS (1) A hard error occurred in the low level disk I/O layer */
178
return EIO; /* POSIX Input/output error (POSIX.1) */
179
180
case FR_INT_ERR: /* FatFS (2) Assertion failed */
181
return EPERM; /* POSIX Operation not permitted (POSIX.1) */
182
183
case FR_NOT_READY: /* FatFS (3) The physical drive cannot work */
184
return EBUSY; /* POSIX Device or resource busy (POSIX.1) */
185
186
case FR_NO_FILE: /* FatFS (4) Could not find the file */
187
return ENOENT; /* POSIX No such file or directory (POSIX.1) */
188
189
case FR_NO_PATH: /* FatFS (5) Could not find the path */
190
return ENOENT; /* POSIX No such file or directory (POSIX.1) */
191
192
case FR_INVALID_NAME: /* FatFS (6) The path name format is invalid */
193
return EINVAL; /* POSIX Invalid argument (POSIX.1) */
194
195
case FR_DENIED: /* FatFS (7) Access denied due to prohibited access or directory full */
196
return EACCES; /* POSIX Permission denied (POSIX.1) */
197
198
case FR_EXIST: /* file exists */
199
return EEXIST; /* file exists */
200
201
case FR_INVALID_OBJECT: /* FatFS (9) The file/directory object is invalid */
202
return EINVAL; /* POSIX Invalid argument (POSIX.1) */
203
204
case FR_WRITE_PROTECTED: /* FatFS (10) The physical drive is write protected */
205
return EROFS; /* POSIX Read-only filesystem (POSIX.1) */
206
207
case FR_INVALID_DRIVE: /* FatFS (11) The logical drive number is invalid */
208
return ENXIO; /* POSIX No such device or address (POSIX.1) */
209
210
case FR_NOT_ENABLED: /* FatFS (12) The volume has no work area */
211
return ENOSPC; /* POSIX No space left on device (POSIX.1) */
212
213
case FR_NO_FILESYSTEM: /* FatFS (13) There is no valid FAT volume */
214
return ENXIO; /* POSIX No such device or address (POSIX.1) */
215
216
case FR_MKFS_ABORTED: /* FatFS (14) The f_mkfs() aborted due to any parameter error */
217
return EINVAL; /* POSIX Invalid argument (POSIX.1) */
218
219
case FR_TIMEOUT: /* FatFS (15) Could not get a grant to access the volume within defined period */
220
return EBUSY; /* POSIX Device or resource busy (POSIX.1) */
221
222
case FR_LOCKED: /* FatFS (16) The operation is rejected according to the file sharing policy */
223
return EBUSY; /* POSIX Device or resource busy (POSIX.1) */
224
225
226
case FR_NOT_ENOUGH_CORE: /* FatFS (17) LFN working buffer could not be allocated */
227
return ENOMEM; /* POSIX Not enough space (POSIX.1) */
228
229
case FR_TOO_MANY_OPEN_FILES:/* FatFS (18) Number of open files > _FS_SHARE */
230
return EMFILE; /* POSIX Too many open files (POSIX.1) */
231
232
case FR_INVALID_PARAMETER:/* FatFS (19) Given parameter is invalid */
233
return EINVAL; /* POSIX Invalid argument (POSIX.1) */
234
235
}
236
return EBADMSG; /* POSIX Bad message (POSIX.1) */
237
}
238
239
// check for a remount and return -1 if it fails
240
#define CHECK_REMOUNT() do { if (remount_needed && !remount_file_system()) { errno = EIO; return -1; }} while (0)
241
#define CHECK_REMOUNT_NULL() do { if (remount_needed && !remount_file_system()) { errno = EIO; return NULL; }} while (0)
242
243
// we allow for IO retries if either not armed or not in main thread
244
#define RETRY_ALLOWED() (!hal.scheduler->in_main_thread() || !hal.util->get_soft_armed())
245
246
/*
247
try to remount the file system on disk error
248
*/
249
static bool remount_file_system(void)
250
{
251
EXPECT_DELAY_MS(3000);
252
if (!remount_needed) {
253
sdcard_stop();
254
}
255
if (!sdcard_retry()) {
256
remount_needed = true;
257
return false;
258
}
259
remount_needed = false;
260
for (uint16_t i=0; i<MAX_FILES; i++) {
261
FAT_FILE *f = file_table[i];
262
if (!f) {
263
continue;
264
}
265
FIL *fh = f->fh;
266
FSIZE_t offset = fh->fptr;
267
uint8_t flags = fh->flag & (FA_READ | FA_WRITE);
268
269
memset(fh, 0, sizeof(*fh));
270
if (flags & FA_WRITE) {
271
// the file may not have been created yet on the sdcard
272
flags |= FA_OPEN_ALWAYS;
273
}
274
FRESULT res = f_open(fh, f->name, flags);
275
debug("reopen %s flags=0x%x ofs=%u -> %d\n", f->name, unsigned(flags), unsigned(offset), int(res));
276
if (res == FR_OK) {
277
f_lseek(fh, offset);
278
}
279
}
280
return true;
281
}
282
283
int AP_Filesystem_FATFS::open(const char *pathname, int flags, bool allow_absolute_path)
284
{
285
int fileno;
286
int fatfs_modes;
287
FAT_FILE *stream;
288
FIL *fh;
289
int res;
290
291
FS_CHECK_ALLOWED(-1);
292
WITH_SEMAPHORE(sem);
293
294
CHECK_REMOUNT();
295
296
errno = 0;
297
debug("Open %s 0x%x", pathname, flags);
298
299
if ((flags & O_ACCMODE) == O_RDWR) {
300
fatfs_modes = FA_READ | FA_WRITE;
301
} else if ((flags & O_ACCMODE) == O_RDONLY) {
302
fatfs_modes = FA_READ;
303
} else {
304
fatfs_modes = FA_WRITE;
305
}
306
307
if (flags & O_CREAT) {
308
if (flags & O_TRUNC) {
309
fatfs_modes |= FA_CREATE_ALWAYS;
310
} else {
311
fatfs_modes |= FA_OPEN_ALWAYS;
312
}
313
}
314
315
fileno = new_file_descriptor(pathname);
316
317
// checks if fileno out of bounds
318
stream = fileno_to_stream(fileno);
319
if (stream == nullptr) {
320
free_file_descriptor(fileno);
321
return -1;
322
}
323
324
// fileno_to_fatfs checks for fileno out of bounds
325
fh = fileno_to_fatfs(fileno);
326
if (fh == nullptr) {
327
free_file_descriptor(fileno);
328
errno = EBADF;
329
return -1;
330
}
331
res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));
332
if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
333
// one retry on disk error
334
hal.scheduler->delay(100);
335
if (remount_file_system()) {
336
res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));
337
}
338
}
339
if (res != FR_OK) {
340
errno = fatfs_to_errno((FRESULT)res);
341
free_file_descriptor(fileno);
342
return -1;
343
}
344
if (flags & O_APPEND) {
345
/// Seek to end of the file
346
res = f_lseek(fh, f_size(fh));
347
if (res != FR_OK) {
348
errno = fatfs_to_errno((FRESULT)res);
349
f_close(fh);
350
free_file_descriptor(fileno);
351
return -1;
352
}
353
}
354
355
debug("Open %s -> %d", pathname, fileno);
356
357
return fileno;
358
}
359
360
int AP_Filesystem_FATFS::close(int fileno)
361
{
362
FAT_FILE *stream;
363
FIL *fh;
364
int res;
365
366
FS_CHECK_ALLOWED(-1);
367
WITH_SEMAPHORE(sem);
368
369
errno = 0;
370
371
// checks if fileno out of bounds
372
stream = fileno_to_stream(fileno);
373
if (stream == nullptr) {
374
return -1;
375
}
376
377
// fileno_to_fatfs checks for fileno out of bounds
378
fh = fileno_to_fatfs(fileno);
379
if (fh == nullptr) {
380
return -1;
381
}
382
res = f_close(fh);
383
free_file_descriptor(fileno);
384
if (res != FR_OK) {
385
errno = fatfs_to_errno((FRESULT)res);
386
return -1;
387
}
388
return 0;
389
}
390
391
int32_t AP_Filesystem_FATFS::read(int fd, void *buf, uint32_t count)
392
{
393
UINT bytes = count;
394
int res;
395
FIL *fh;
396
397
FS_CHECK_ALLOWED(-1);
398
WITH_SEMAPHORE(sem);
399
400
CHECK_REMOUNT();
401
402
if (count > 0) {
403
*(char *) buf = 0;
404
}
405
406
errno = 0;
407
408
// fileno_to_fatfs checks for fd out of bounds
409
fh = fileno_to_fatfs(fd);
410
if (fh == nullptr) {
411
errno = EBADF;
412
return -1;
413
}
414
415
UINT total = 0;
416
do {
417
UINT size = 0;
418
UINT n = bytes;
419
if (!mem_is_dma_safe(buf, count, true)) {
420
n = MIN(bytes, MAX_IO_SIZE);
421
}
422
res = f_read(fh, (void *)buf, n, &size);
423
if (res != FR_OK) {
424
errno = fatfs_to_errno((FRESULT)res);
425
return -1;
426
}
427
if (size == 0) {
428
break;
429
}
430
if (size > n) {
431
errno = EIO;
432
return -1;
433
}
434
total += size;
435
buf = (void *)(((uint8_t *)buf)+size);
436
bytes -= size;
437
if (size < n) {
438
break;
439
}
440
} while (bytes > 0);
441
return (ssize_t)total;
442
}
443
444
int32_t AP_Filesystem_FATFS::write(int fd, const void *buf, uint32_t count)
445
{
446
UINT bytes = count;
447
FRESULT res;
448
FIL *fh;
449
errno = 0;
450
451
FS_CHECK_ALLOWED(-1);
452
WITH_SEMAPHORE(sem);
453
454
CHECK_REMOUNT();
455
456
// fileno_to_fatfs checks for fd out of bounds
457
fh = fileno_to_fatfs(fd);
458
if (fh == nullptr) {
459
errno = EBADF;
460
return -1;
461
}
462
463
UINT total = 0;
464
do {
465
UINT n = bytes;
466
if (!mem_is_dma_safe(buf, count, true)) {
467
n = MIN(bytes, MAX_IO_SIZE);
468
}
469
UINT size = 0;
470
res = f_write(fh, buf, n, &size);
471
if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
472
// one retry on disk error
473
hal.scheduler->delay(100);
474
if (remount_file_system()) {
475
res = f_write(fh, buf, n, &size);
476
}
477
}
478
if (size > n || size == 0) {
479
errno = EIO;
480
return -1;
481
}
482
if (res != FR_OK || size > n) {
483
errno = fatfs_to_errno(res);
484
return -1;
485
}
486
total += size;
487
buf = (void *)(((uint8_t *)buf)+size);
488
bytes -= size;
489
if (size < n) {
490
break;
491
}
492
} while (bytes > 0);
493
return (ssize_t)total;
494
}
495
496
int AP_Filesystem_FATFS::fsync(int fileno)
497
{
498
FAT_FILE *stream;
499
FIL *fh;
500
int res;
501
502
FS_CHECK_ALLOWED(-1);
503
WITH_SEMAPHORE(sem);
504
505
errno = 0;
506
507
// checks if fileno out of bounds
508
stream = fileno_to_stream(fileno);
509
if (stream == nullptr) {
510
return -1;
511
}
512
513
// fileno_to_fatfs checks for fileno out of bounds
514
fh = fileno_to_fatfs(fileno);
515
if (fh == nullptr) {
516
return -1;
517
}
518
res = f_sync(fh);
519
if (res != FR_OK) {
520
errno = fatfs_to_errno((FRESULT)res);
521
return -1;
522
}
523
return 0;
524
}
525
526
off_t AP_Filesystem_FATFS::lseek(int fileno, off_t position, int whence)
527
{
528
FRESULT res;
529
FIL *fh;
530
errno = 0;
531
532
FS_CHECK_ALLOWED(-1);
533
WITH_SEMAPHORE(sem);
534
535
// fileno_to_fatfs checks for fd out of bounds
536
fh = fileno_to_fatfs(fileno);
537
if (fh == nullptr) {
538
errno = EMFILE;
539
return -1;
540
}
541
if (isatty_(fileno)) {
542
return -1;
543
}
544
545
if (whence == SEEK_END) {
546
position += f_size(fh);
547
} else if (whence==SEEK_CUR) {
548
position += fh->fptr;
549
}
550
551
res = f_lseek(fh, position);
552
if (res) {
553
errno = fatfs_to_errno(res);
554
return -1;
555
}
556
return fh->fptr;
557
}
558
559
static time_t fat_time_to_unix(uint16_t date, uint16_t time)
560
{
561
struct tm tp;
562
time_t unix;
563
564
memset(&tp, 0, sizeof(struct tm));
565
566
tp.tm_sec = (time << 1) & 0x3e; // 2 second resolution
567
tp.tm_min = ((time >> 5) & 0x3f);
568
tp.tm_hour = ((time >> 11) & 0x1f);
569
tp.tm_mday = (date & 0x1f);
570
tp.tm_mon = ((date >> 5) & 0x0f) - 1;
571
tp.tm_year = ((date >> 9) & 0x7f) + 80;
572
unix = ap_mktime(&tp);
573
return unix;
574
}
575
576
int AP_Filesystem_FATFS::stat(const char *name, struct stat *buf)
577
{
578
FILINFO info;
579
int res;
580
time_t epoch;
581
uint16_t mode;
582
583
FS_CHECK_ALLOWED(-1);
584
WITH_SEMAPHORE(sem);
585
586
CHECK_REMOUNT();
587
588
errno = 0;
589
590
// f_stat does not handle / or . as root directory
591
if (strcmp(name,"/") == 0 || strcmp(name,".") == 0) {
592
buf->st_atime = 0;
593
buf->st_mtime = 0;
594
buf->st_ctime = 0;
595
buf->st_uid= 0;
596
buf->st_gid= 0;
597
buf->st_size = 0;
598
buf->st_mode = S_IFDIR;
599
return 0;
600
}
601
602
res = f_stat(name, &info);
603
if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
604
// one retry on disk error
605
if (remount_file_system()) {
606
res = f_stat(name, &info);
607
}
608
}
609
if (res != FR_OK) {
610
errno = fatfs_to_errno((FRESULT)res);
611
return -1;
612
}
613
614
buf->st_size = info.fsize;
615
epoch = fat_time_to_unix(info.fdate, info.ftime);
616
buf->st_atime = epoch; // Access time
617
buf->st_mtime = epoch; // Modification time
618
buf->st_ctime = epoch; // Creation time
619
620
// We only handle read only case
621
mode = (FATFS_R | FATFS_X);
622
if (!(info.fattrib & AM_RDO)) {
623
mode |= (FATFS_W); // enable write if NOT read only
624
}
625
626
if (info.fattrib & AM_SYS) {
627
buf->st_uid= 0;
628
buf->st_gid= 0;
629
}
630
{
631
buf->st_uid=1000;
632
buf->st_gid=1000;
633
}
634
635
if (info.fattrib & AM_DIR) {
636
mode |= S_IFDIR;
637
} else {
638
mode |= S_IFREG;
639
}
640
buf->st_mode = mode;
641
642
return 0;
643
}
644
645
int AP_Filesystem_FATFS::unlink(const char *pathname)
646
{
647
FS_CHECK_ALLOWED(-1);
648
WITH_SEMAPHORE(sem);
649
650
errno = 0;
651
int res = f_unlink(pathname);
652
if (res != FR_OK) {
653
errno = fatfs_to_errno((FRESULT)res);
654
return -1;
655
}
656
return 0;
657
}
658
659
int AP_Filesystem_FATFS::mkdir(const char *pathname)
660
{
661
FS_CHECK_ALLOWED(-1);
662
WITH_SEMAPHORE(sem);
663
664
errno = 0;
665
666
int res = f_mkdir(pathname);
667
if (res != FR_OK) {
668
errno = fatfs_to_errno((FRESULT)res);
669
return -1;
670
}
671
672
return 0;
673
}
674
675
int AP_Filesystem_FATFS::rename(const char *oldpath, const char *newpath)
676
{
677
FS_CHECK_ALLOWED(-1);
678
WITH_SEMAPHORE(sem);
679
680
errno = 0;
681
682
int res = f_rename(oldpath, newpath);
683
if (res != FR_OK) {
684
errno = fatfs_to_errno((FRESULT)res);
685
return -1;
686
}
687
688
return 0;
689
}
690
691
/*
692
wrapper structure to associate a dirent with a DIR
693
*/
694
struct DIR_Wrapper {
695
DIR d; // must be first structure element
696
struct dirent de;
697
};
698
699
void *AP_Filesystem_FATFS::opendir(const char *pathdir)
700
{
701
FS_CHECK_ALLOWED(nullptr);
702
WITH_SEMAPHORE(sem);
703
704
CHECK_REMOUNT_NULL();
705
706
debug("Opendir %s", pathdir);
707
struct DIR_Wrapper *ret = NEW_NOTHROW DIR_Wrapper;
708
if (!ret) {
709
return nullptr;
710
}
711
int res = f_opendir(&ret->d, pathdir);
712
if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
713
// one retry on disk error
714
if (remount_file_system()) {
715
res = f_opendir(&ret->d, pathdir);
716
}
717
}
718
if (res != FR_OK) {
719
errno = fatfs_to_errno((FRESULT)res);
720
delete ret;
721
return nullptr;
722
}
723
debug("Opendir %s -> %p", pathdir, ret);
724
return &ret->d;
725
}
726
727
struct dirent *AP_Filesystem_FATFS::readdir(void *dirp_void)
728
{
729
FS_CHECK_ALLOWED(nullptr);
730
WITH_SEMAPHORE(sem);
731
DIR *dirp = (DIR *)dirp_void;
732
733
struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;
734
if (!d) {
735
errno = EINVAL;
736
return nullptr;
737
}
738
FILINFO fno;
739
int len;
740
int res;
741
742
d->de.d_name[0] = 0;
743
res = f_readdir(dirp, &fno);
744
if (res != FR_OK || fno.fname[0] == 0) {
745
errno = fatfs_to_errno((FRESULT)res);
746
return nullptr;
747
}
748
len = strlen(fno.fname);
749
strncpy_noterm(d->de.d_name,fno.fname,len);
750
d->de.d_name[len] = 0;
751
if (fno.fattrib & AM_DIR) {
752
d->de.d_type = DT_DIR;
753
} else {
754
d->de.d_type = DT_REG;
755
}
756
return &d->de;
757
}
758
759
int AP_Filesystem_FATFS::closedir(void *dirp_void)
760
{
761
DIR *dirp = (DIR *)dirp_void;
762
FS_CHECK_ALLOWED(-1);
763
WITH_SEMAPHORE(sem);
764
765
struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;
766
if (!d) {
767
errno = EINVAL;
768
return -1;
769
}
770
int res = f_closedir (dirp);
771
delete d;
772
if (res != FR_OK) {
773
errno = fatfs_to_errno((FRESULT)res);
774
return -1;
775
}
776
debug("closedir");
777
return 0;
778
}
779
780
// return free disk space in bytes
781
int64_t AP_Filesystem_FATFS::disk_free(const char *path)
782
{
783
FS_CHECK_ALLOWED(-1);
784
WITH_SEMAPHORE(sem);
785
786
FATFS *fs;
787
DWORD fre_clust, fre_sect;
788
789
CHECK_REMOUNT();
790
791
/* Get volume information and free clusters of drive 1 */
792
FRESULT res = f_getfree("/", &fre_clust, &fs);
793
if (res) {
794
return res;
795
}
796
797
/* Get total sectors and free sectors */
798
fre_sect = fre_clust * fs->csize;
799
return (int64_t)(fre_sect)*512;
800
}
801
802
// return total disk space in bytes
803
int64_t AP_Filesystem_FATFS::disk_space(const char *path)
804
{
805
FS_CHECK_ALLOWED(-1);
806
WITH_SEMAPHORE(sem);
807
808
CHECK_REMOUNT();
809
810
FATFS *fs;
811
DWORD fre_clust, tot_sect;
812
813
/* Get volume information and free clusters of drive 1 */
814
FRESULT res = f_getfree("/", &fre_clust, &fs);
815
if (res) {
816
return -1;
817
}
818
819
/* Get total sectors and free sectors */
820
tot_sect = (fs->n_fatent - 2) * fs->csize;
821
return (int64_t)(tot_sect)*512;
822
}
823
824
/*
825
convert unix time_t to FATFS timestamp
826
*/
827
static void unix_time_to_fat(time_t epoch, uint16_t &date, uint16_t &time)
828
{
829
struct tm tmd {};
830
struct tm *t = gmtime_r((time_t *)&epoch, &tmd);
831
832
/* Pack date and time into a uint32_t variable */
833
date = ((uint16_t)(t->tm_year - 80) << 9)
834
| (((uint16_t)t->tm_mon+1) << 5)
835
| (((uint16_t)t->tm_mday));
836
837
time = ((uint16_t)t->tm_hour << 11)
838
| ((uint16_t)t->tm_min << 5)
839
| ((uint16_t)t->tm_sec >> 1);
840
}
841
842
/*
843
set mtime on a file
844
*/
845
bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_sec)
846
{
847
FILINFO fno;
848
uint16_t fdate, ftime;
849
850
unix_time_to_fat(mtime_sec, fdate, ftime);
851
852
fno.fdate = fdate;
853
fno.ftime = ftime;
854
855
FS_CHECK_ALLOWED(false);
856
WITH_SEMAPHORE(sem);
857
858
return f_utime(filename, (FILINFO *)&fno) == FR_OK;
859
}
860
861
/*
862
retry mount of filesystem if needed
863
*/
864
bool AP_Filesystem_FATFS::retry_mount(void)
865
{
866
FS_CHECK_ALLOWED(false);
867
WITH_SEMAPHORE(sem);
868
return sdcard_retry();
869
}
870
871
/*
872
unmount filesystem for reboot
873
*/
874
void AP_Filesystem_FATFS::unmount(void)
875
{
876
WITH_SEMAPHORE(sem);
877
return sdcard_stop();
878
}
879
880
/*
881
format sdcard
882
*/
883
bool AP_Filesystem_FATFS::format(void)
884
{
885
#if FF_USE_MKFS
886
WITH_SEMAPHORE(sem);
887
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FATFS::format_handler, void));
888
// the format is handled asynchronously, we inform user of success
889
// via a text message. format_status can be polled for progress
890
format_status = FormatStatus::PENDING;
891
return true;
892
#else
893
return false;
894
#endif
895
}
896
897
/*
898
format sdcard
899
*/
900
void AP_Filesystem_FATFS::format_handler(void)
901
{
902
#if FF_USE_MKFS
903
if (format_status != FormatStatus::PENDING) {
904
return;
905
}
906
WITH_SEMAPHORE(sem);
907
format_status = FormatStatus::IN_PROGRESS;
908
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting SDCard");
909
uint8_t *buf = (uint8_t *)hal.util->malloc_type(FF_MAX_SS, AP_HAL::Util::MEM_DMA_SAFE);
910
if (buf == nullptr) {
911
return;
912
}
913
// format first disk
914
auto ret = f_mkfs("0:", 0, buf, FF_MAX_SS);
915
hal.util->free_type(buf, FF_MAX_SS, AP_HAL::Util::MEM_DMA_SAFE);
916
if (ret == FR_OK) {
917
format_status = FormatStatus::SUCCESS;
918
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format: OK");
919
} else {
920
format_status = FormatStatus::FAILURE;
921
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format: Failed (%d)", int(ret));
922
}
923
sdcard_stop();
924
sdcard_retry();
925
#endif
926
}
927
928
// returns true if we are currently formatting the SD card:
929
AP_Filesystem_Backend::FormatStatus AP_Filesystem_FATFS::get_format_status(void) const
930
{
931
// note that format_handler holds sem, so we can't take it here.
932
return format_status;
933
}
934
935
/*
936
convert POSIX errno to text with user message.
937
*/
938
char *strerror(int errnum)
939
{
940
#define SWITCH_ERROR(errno) case errno: return const_cast<char *>(#errno); break
941
switch (errnum) {
942
SWITCH_ERROR(EPERM);
943
SWITCH_ERROR(ENOENT);
944
SWITCH_ERROR(ESRCH);
945
SWITCH_ERROR(EINTR);
946
SWITCH_ERROR(EIO);
947
SWITCH_ERROR(ENXIO);
948
SWITCH_ERROR(E2BIG);
949
SWITCH_ERROR(ENOEXEC);
950
SWITCH_ERROR(EBADF);
951
SWITCH_ERROR(ECHILD);
952
SWITCH_ERROR(EAGAIN);
953
SWITCH_ERROR(ENOMEM);
954
SWITCH_ERROR(EACCES);
955
SWITCH_ERROR(EFAULT);
956
#ifdef ENOTBLK
957
SWITCH_ERROR(ENOTBLK);
958
#endif // ENOTBLK
959
SWITCH_ERROR(EBUSY);
960
SWITCH_ERROR(EEXIST);
961
SWITCH_ERROR(EXDEV);
962
SWITCH_ERROR(ENODEV);
963
SWITCH_ERROR(ENOTDIR);
964
SWITCH_ERROR(EISDIR);
965
SWITCH_ERROR(EINVAL);
966
SWITCH_ERROR(ENFILE);
967
SWITCH_ERROR(EMFILE);
968
SWITCH_ERROR(ENOTTY);
969
SWITCH_ERROR(ETXTBSY);
970
SWITCH_ERROR(EFBIG);
971
SWITCH_ERROR(ENOSPC);
972
SWITCH_ERROR(ESPIPE);
973
SWITCH_ERROR(EROFS);
974
SWITCH_ERROR(EMLINK);
975
SWITCH_ERROR(EPIPE);
976
SWITCH_ERROR(EDOM);
977
SWITCH_ERROR(ERANGE);
978
SWITCH_ERROR(EBADMSG);
979
}
980
981
#undef SWITCH_ERROR
982
983
return NULL;
984
}
985
986
#endif // AP_FILESYSTEM_FATFS_ENABLED
987
988