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