AP_Filesystem_FATFS.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867
  1. /*
  2. ArduPilot filesystem interface for systems using the FATFS filesystem
  3. */
  4. #include "AP_Filesystem.h"
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <stdio.h>
  7. #if HAVE_FILESYSTEM_SUPPORT && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  8. #include <AP_HAL_ChibiOS/sdcard.h>
  9. #if 0
  10. #define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  11. #else
  12. #define debug(fmt, args ...)
  13. #endif
  14. extern const AP_HAL::HAL& hal;
  15. static bool remount_needed;
  16. #define FATFS_R (S_IRUSR | S_IRGRP | S_IROTH) /*< FatFs Read perms */
  17. #define FATFS_W (S_IWUSR | S_IWGRP | S_IWOTH) /*< FatFs Write perms */
  18. #define FATFS_X (S_IXUSR | S_IXGRP | S_IXOTH) /*< FatFs Execute perms */
  19. // use a semaphore to ensure that only one filesystem operation is
  20. // happening at a time. A recursive semaphore is used to cope with the
  21. // mkdir() inside sdcard_retry()
  22. static HAL_Semaphore_Recursive sem;
  23. typedef struct {
  24. FIL *fh;
  25. char *name;
  26. } FAT_FILE;
  27. #define MAX_FILES 16
  28. static FAT_FILE *file_table[MAX_FILES];
  29. static bool isatty(int fileno)
  30. {
  31. if (fileno >= 0 && fileno <= 2) {
  32. return true;
  33. }
  34. return false;
  35. }
  36. /*
  37. allocate a file descriptor
  38. */
  39. static int new_file_descriptor(const char *pathname)
  40. {
  41. int i;
  42. FAT_FILE *stream;
  43. FIL *fh;
  44. for (i=0; i<MAX_FILES; ++i) {
  45. if (isatty(i)) {
  46. continue;
  47. }
  48. if ( file_table[i] == NULL) {
  49. stream = (FAT_FILE *) calloc(sizeof(FAT_FILE),1);
  50. if (stream == NULL) {
  51. errno = ENOMEM;
  52. return -1;
  53. }
  54. fh = (FIL *) calloc(sizeof(FIL),1);
  55. if (fh == NULL) {
  56. free(stream);
  57. errno = ENOMEM;
  58. return -1;
  59. }
  60. char *fname = (char *)malloc(strlen(pathname)+1);
  61. if (fname == NULL) {
  62. free(fh);
  63. free(stream);
  64. errno = ENOMEM;
  65. return -1;
  66. }
  67. strcpy(fname, pathname);
  68. stream->name = fname;
  69. file_table[i] = stream;
  70. stream->fh = fh;
  71. return i;
  72. }
  73. }
  74. errno = ENFILE;
  75. return -1;
  76. }
  77. static FAT_FILE *fileno_to_stream(int fileno)
  78. {
  79. FAT_FILE *stream;
  80. if (fileno < 0 || fileno >= MAX_FILES) {
  81. errno = EBADF;
  82. return nullptr;
  83. }
  84. stream = file_table[fileno];
  85. if (stream == NULL) {
  86. errno = EBADF;
  87. return nullptr;
  88. }
  89. return stream;
  90. }
  91. static int free_file_descriptor(int fileno)
  92. {
  93. FAT_FILE *stream;
  94. FIL *fh;
  95. if (isatty( fileno )) {
  96. errno = EBADF;
  97. return -1;
  98. }
  99. // checks if fileno out of bounds
  100. stream = fileno_to_stream(fileno);
  101. if (stream == NULL) {
  102. return -1;
  103. }
  104. fh = stream->fh;
  105. if (fh != NULL) {
  106. free(fh);
  107. }
  108. free(stream->name);
  109. stream->name = NULL;
  110. file_table[fileno] = NULL;
  111. free(stream);
  112. return fileno;
  113. }
  114. static FIL *fileno_to_fatfs(int fileno)
  115. {
  116. FAT_FILE *stream;
  117. FIL *fh;
  118. if (isatty( fileno )) {
  119. errno = EBADF;
  120. return nullptr;
  121. }
  122. // checks if fileno out of bounds
  123. stream = fileno_to_stream(fileno);
  124. if ( stream == NULL ) {
  125. return nullptr;
  126. }
  127. fh = stream->fh;
  128. if (fh == NULL) {
  129. errno = EBADF;
  130. return nullptr;
  131. }
  132. return fh;
  133. }
  134. static int fatfs_to_errno( FRESULT Result )
  135. {
  136. switch ( Result ) {
  137. case FR_OK: /* FatFS (0) Succeeded */
  138. return 0; /* POSIX OK */
  139. case FR_DISK_ERR: /* FatFS (1) A hard error occurred in the low level disk I/O layer */
  140. return EIO; /* POSIX Input/output error (POSIX.1) */
  141. case FR_INT_ERR: /* FatFS (2) Assertion failed */
  142. return EPERM; /* POSIX Operation not permitted (POSIX.1) */
  143. case FR_NOT_READY: /* FatFS (3) The physical drive cannot work */
  144. return EBUSY; /* POSIX Device or resource busy (POSIX.1) */
  145. case FR_NO_FILE: /* FatFS (4) Could not find the file */
  146. return ENOENT; /* POSIX No such file or directory (POSIX.1) */
  147. case FR_NO_PATH: /* FatFS (5) Could not find the path */
  148. return ENOENT; /* POSIX No such file or directory (POSIX.1) */
  149. case FR_INVALID_NAME: /* FatFS (6) The path name format is invalid */
  150. return EINVAL; /* POSIX Invalid argument (POSIX.1) */
  151. case FR_DENIED: /* FatFS (7) Access denied due to prohibited access or directory full */
  152. return EACCES; /* POSIX Permission denied (POSIX.1) */
  153. case FR_EXIST: /* file exists */
  154. return EEXIST; /* file exists */
  155. case FR_INVALID_OBJECT: /* FatFS (9) The file/directory object is invalid */
  156. return EINVAL; /* POSIX Invalid argument (POSIX.1) */
  157. case FR_WRITE_PROTECTED: /* FatFS (10) The physical drive is write protected */
  158. return EROFS; /* POSIX Read-only filesystem (POSIX.1) */
  159. case FR_INVALID_DRIVE: /* FatFS (11) The logical drive number is invalid */
  160. return ENXIO; /* POSIX No such device or address (POSIX.1) */
  161. case FR_NOT_ENABLED: /* FatFS (12) The volume has no work area */
  162. return ENOSPC; /* POSIX No space left on device (POSIX.1) */
  163. case FR_NO_FILESYSTEM: /* FatFS (13) There is no valid FAT volume */
  164. return ENXIO; /* POSIX No such device or address (POSIX.1) */
  165. case FR_MKFS_ABORTED: /* FatFS (14) The f_mkfs() aborted due to any parameter error */
  166. return EINVAL; /* POSIX Invalid argument (POSIX.1) */
  167. case FR_TIMEOUT: /* FatFS (15) Could not get a grant to access the volume within defined period */
  168. return EBUSY; /* POSIX Device or resource busy (POSIX.1) */
  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. case FR_NOT_ENOUGH_CORE: /* FatFS (17) LFN working buffer could not be allocated */
  172. return ENOMEM; /* POSIX Not enough space (POSIX.1) */
  173. case FR_TOO_MANY_OPEN_FILES:/* FatFS (18) Number of open files > _FS_SHARE */
  174. return EMFILE; /* POSIX Too many open files (POSIX.1) */
  175. case FR_INVALID_PARAMETER:/* FatFS (19) Given parameter is invalid */
  176. return EINVAL; /* POSIX Invalid argument (POSIX.1) */
  177. }
  178. return EBADMSG; /* POSIX Bad message (POSIX.1) */
  179. }
  180. // check for a remount and return -1 if it fails
  181. #define CHECK_REMOUNT() do { if (remount_needed && !remount_file_system()) { errno = EIO; return -1; }} while (0)
  182. #define CHECK_REMOUNT_NULL() do { if (remount_needed && !remount_file_system()) { errno = EIO; return NULL; }} while (0)
  183. // we allow for IO retries if either not armed or not in main thread
  184. #define RETRY_ALLOWED() (!hal.scheduler->in_main_thread() || !hal.util->get_soft_armed())
  185. /*
  186. try to remount the file system on disk error
  187. */
  188. static bool remount_file_system(void)
  189. {
  190. EXPECT_DELAY_MS(3000);
  191. if (!remount_needed) {
  192. sdcard_stop();
  193. }
  194. if (!sdcard_retry()) {
  195. remount_needed = true;
  196. EXPECT_DELAY_MS(0);
  197. return false;
  198. }
  199. remount_needed = false;
  200. for (uint16_t i=0; i<MAX_FILES; i++) {
  201. FAT_FILE *f = file_table[i];
  202. if (!f) {
  203. continue;
  204. }
  205. FIL *fh = f->fh;
  206. FSIZE_t offset = fh->fptr;
  207. uint8_t flags = fh->flag & (FA_READ | FA_WRITE);
  208. memset(fh, 0, sizeof(*fh));
  209. if (flags & FA_WRITE) {
  210. // the file may not have been created yet on the sdcard
  211. flags |= FA_OPEN_ALWAYS;
  212. }
  213. FRESULT res = f_open(fh, f->name, flags);
  214. debug("reopen %s flags=0x%x ofs=%u -> %d\n", f->name, unsigned(flags), unsigned(offset), int(res));
  215. if (res == FR_OK) {
  216. f_lseek(fh, offset);
  217. }
  218. }
  219. EXPECT_DELAY_MS(0);
  220. return true;
  221. }
  222. int AP_Filesystem::open(const char *pathname, int flags)
  223. {
  224. int fileno;
  225. int fatfs_modes;
  226. FAT_FILE *stream;
  227. FIL *fh;
  228. int res;
  229. WITH_SEMAPHORE(sem);
  230. CHECK_REMOUNT();
  231. errno = 0;
  232. debug("Open %s 0x%x", pathname, flags);
  233. if ((flags & O_ACCMODE) == O_RDWR) {
  234. fatfs_modes = FA_READ | FA_WRITE;
  235. } else if ((flags & O_ACCMODE) == O_RDONLY) {
  236. fatfs_modes = FA_READ;
  237. } else {
  238. fatfs_modes = FA_WRITE;
  239. }
  240. if (flags & O_CREAT) {
  241. if (flags & O_TRUNC) {
  242. fatfs_modes |= FA_CREATE_ALWAYS;
  243. } else {
  244. fatfs_modes |= FA_OPEN_ALWAYS;
  245. }
  246. }
  247. fileno = new_file_descriptor(pathname);
  248. // checks if fileno out of bounds
  249. stream = fileno_to_stream(fileno);
  250. if (stream == NULL) {
  251. free_file_descriptor(fileno);
  252. return -1;
  253. }
  254. // fileno_to_fatfs checks for fileno out of bounds
  255. fh = fileno_to_fatfs(fileno);
  256. if (fh == NULL) {
  257. free_file_descriptor(fileno);
  258. errno = EBADF;
  259. return -1;
  260. }
  261. res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));
  262. if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
  263. // one retry on disk error
  264. hal.scheduler->delay(100);
  265. if (remount_file_system()) {
  266. res = f_open(fh, pathname, (BYTE) (fatfs_modes & 0xff));
  267. }
  268. }
  269. if (res != FR_OK) {
  270. errno = fatfs_to_errno((FRESULT)res);
  271. free_file_descriptor(fileno);
  272. return -1;
  273. }
  274. if (flags & O_APPEND) {
  275. /// Seek to end of the file
  276. res = f_lseek(fh, f_size(fh));
  277. if (res != FR_OK) {
  278. errno = fatfs_to_errno((FRESULT)res);
  279. f_close(fh);
  280. free_file_descriptor(fileno);
  281. return -1;
  282. }
  283. }
  284. debug("Open %s -> %d", pathname, fileno);
  285. return fileno;
  286. }
  287. int AP_Filesystem::close(int fileno)
  288. {
  289. FAT_FILE *stream;
  290. FIL *fh;
  291. int res;
  292. WITH_SEMAPHORE(sem);
  293. errno = 0;
  294. // checks if fileno out of bounds
  295. stream = fileno_to_stream(fileno);
  296. if (stream == NULL) {
  297. return -1;
  298. }
  299. // fileno_to_fatfs checks for fileno out of bounds
  300. fh = fileno_to_fatfs(fileno);
  301. if (fh == NULL) {
  302. return -1;
  303. }
  304. res = f_close(fh);
  305. free_file_descriptor(fileno);
  306. if (res != FR_OK) {
  307. errno = fatfs_to_errno((FRESULT)res);
  308. return -1;
  309. }
  310. return 0;
  311. }
  312. ssize_t AP_Filesystem::read(int fd, void *buf, size_t count)
  313. {
  314. UINT size;
  315. UINT bytes = count;
  316. int res;
  317. FIL *fh;
  318. WITH_SEMAPHORE(sem);
  319. CHECK_REMOUNT();
  320. if (count > 0) {
  321. *(char *) buf = 0;
  322. }
  323. errno = 0;
  324. // fileno_to_fatfs checks for fd out of bounds
  325. fh = fileno_to_fatfs(fd);
  326. if ( fh == NULL ) {
  327. errno = EBADF;
  328. return -1;
  329. }
  330. res = f_read(fh, (void *) buf, bytes, &size);
  331. if (res != FR_OK) {
  332. errno = fatfs_to_errno((FRESULT)res);
  333. return -1;
  334. }
  335. return (ssize_t)size;
  336. }
  337. ssize_t AP_Filesystem::write(int fd, const void *buf, size_t count)
  338. {
  339. UINT size;
  340. UINT bytes = count;
  341. FRESULT res;
  342. FIL *fh;
  343. errno = 0;
  344. WITH_SEMAPHORE(sem);
  345. CHECK_REMOUNT();
  346. // fileno_to_fatfs checks for fd out of bounds
  347. fh = fileno_to_fatfs(fd);
  348. if ( fh == NULL ) {
  349. errno = EBADF;
  350. return -1;
  351. }
  352. res = f_write(fh, buf, bytes, &size);
  353. if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
  354. // one retry on disk error
  355. hal.scheduler->delay(100);
  356. if (remount_file_system()) {
  357. res = f_write(fh, buf, bytes, &size);
  358. }
  359. }
  360. if (res != FR_OK) {
  361. errno = fatfs_to_errno(res);
  362. return -1;
  363. }
  364. return (ssize_t)size;
  365. }
  366. int AP_Filesystem::fsync(int fileno)
  367. {
  368. FAT_FILE *stream;
  369. FIL *fh;
  370. int res;
  371. WITH_SEMAPHORE(sem);
  372. errno = 0;
  373. // checks if fileno out of bounds
  374. stream = fileno_to_stream(fileno);
  375. if (stream == NULL) {
  376. return -1;
  377. }
  378. // fileno_to_fatfs checks for fileno out of bounds
  379. fh = fileno_to_fatfs(fileno);
  380. if (fh == NULL) {
  381. return -1;
  382. }
  383. res = f_sync(fh);
  384. if (res != FR_OK) {
  385. errno = fatfs_to_errno((FRESULT)res);
  386. return -1;
  387. }
  388. return 0;
  389. }
  390. off_t AP_Filesystem::lseek(int fileno, off_t position, int whence)
  391. {
  392. FRESULT res;
  393. FIL *fh;
  394. errno = 0;
  395. WITH_SEMAPHORE(sem);
  396. // fileno_to_fatfs checks for fd out of bounds
  397. fh = fileno_to_fatfs(fileno);
  398. if (fh == NULL) {
  399. errno = EMFILE;
  400. return -1;
  401. }
  402. if (isatty(fileno)) {
  403. return -1;
  404. }
  405. if (whence == SEEK_END) {
  406. position += f_size(fh);
  407. } else if (whence==SEEK_CUR) {
  408. position += fh->fptr;
  409. }
  410. res = f_lseek(fh, position);
  411. if (res) {
  412. errno = fatfs_to_errno(res);
  413. return -1;
  414. }
  415. return fh->fptr;
  416. }
  417. /*
  418. mktime replacement from Samba
  419. */
  420. static time_t replace_mktime(const struct tm *t)
  421. {
  422. time_t epoch = 0;
  423. int n;
  424. int mon [] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }, y, m, i;
  425. const unsigned MINUTE = 60;
  426. const unsigned HOUR = 60*MINUTE;
  427. const unsigned DAY = 24*HOUR;
  428. const unsigned YEAR = 365*DAY;
  429. if (t->tm_year < 70) {
  430. return (time_t)-1;
  431. }
  432. n = t->tm_year + 1900 - 1;
  433. epoch = (t->tm_year - 70) * YEAR +
  434. ((n / 4 - n / 100 + n / 400) - (1969 / 4 - 1969 / 100 + 1969 / 400)) * DAY;
  435. y = t->tm_year + 1900;
  436. m = 0;
  437. for (i = 0; i < t->tm_mon; i++) {
  438. epoch += mon [m] * DAY;
  439. if (m == 1 && y % 4 == 0 && (y % 100 != 0 || y % 400 == 0)) {
  440. epoch += DAY;
  441. }
  442. if (++m > 11) {
  443. m = 0;
  444. y++;
  445. }
  446. }
  447. epoch += (t->tm_mday - 1) * DAY;
  448. epoch += t->tm_hour * HOUR + t->tm_min * MINUTE + t->tm_sec;
  449. return epoch;
  450. }
  451. static time_t fat_time_to_unix(uint16_t date, uint16_t time)
  452. {
  453. struct tm tp;
  454. time_t unix;
  455. memset(&tp, 0, sizeof(struct tm));
  456. tp.tm_sec = (time << 1) & 0x3e; // 2 second resolution
  457. tp.tm_min = ((time >> 5) & 0x3f);
  458. tp.tm_hour = ((time >> 11) & 0x1f);
  459. tp.tm_mday = (date & 0x1f);
  460. tp.tm_mon = ((date >> 5) & 0x0f) - 1;
  461. tp.tm_year = ((date >> 9) & 0x7f) + 80;
  462. unix = replace_mktime( &tp );
  463. return unix;
  464. }
  465. int AP_Filesystem::stat(const char *name, struct stat *buf)
  466. {
  467. FILINFO info;
  468. int res;
  469. time_t epoch;
  470. uint16_t mode;
  471. WITH_SEMAPHORE(sem);
  472. CHECK_REMOUNT();
  473. errno = 0;
  474. // f_stat does not handle / or . as root directory
  475. if (strcmp(name,"/") == 0 || strcmp(name,".") == 0) {
  476. buf->st_atime = 0;
  477. buf->st_mtime = 0;
  478. buf->st_ctime = 0;
  479. buf->st_uid= 0;
  480. buf->st_gid= 0;
  481. buf->st_size = 0;
  482. buf->st_mode = S_IFDIR;
  483. return 0;
  484. }
  485. res = f_stat(name, &info);
  486. if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
  487. // one retry on disk error
  488. if (remount_file_system()) {
  489. res = f_stat(name, &info);
  490. }
  491. }
  492. if (res != FR_OK) {
  493. errno = fatfs_to_errno((FRESULT)res);
  494. return -1;
  495. }
  496. buf->st_size = info.fsize;
  497. epoch = fat_time_to_unix(info.fdate, info.ftime);
  498. buf->st_atime = epoch; // Access time
  499. buf->st_mtime = epoch; // Modification time
  500. buf->st_ctime = epoch; // Creation time
  501. // We only handle read only case
  502. mode = (FATFS_R | FATFS_X);
  503. if ( !(info.fattrib & AM_RDO)) {
  504. mode |= (FATFS_W); // enable write if NOT read only
  505. }
  506. if (info.fattrib & AM_SYS) {
  507. buf->st_uid= 0;
  508. buf->st_gid= 0;
  509. }
  510. {
  511. buf->st_uid=1000;
  512. buf->st_gid=1000;
  513. }
  514. if (info.fattrib & AM_DIR) {
  515. mode |= S_IFDIR;
  516. } else {
  517. mode |= S_IFREG;
  518. }
  519. buf->st_mode = mode;
  520. return 0;
  521. }
  522. int AP_Filesystem::unlink(const char *pathname)
  523. {
  524. WITH_SEMAPHORE(sem);
  525. errno = 0;
  526. int res = f_unlink(pathname);
  527. if (res != FR_OK) {
  528. errno = fatfs_to_errno((FRESULT)res);
  529. return -1;
  530. }
  531. return 0;
  532. }
  533. int AP_Filesystem::mkdir(const char *pathname)
  534. {
  535. WITH_SEMAPHORE(sem);
  536. errno = 0;
  537. int res = f_mkdir(pathname);
  538. if (res != FR_OK) {
  539. errno = fatfs_to_errno((FRESULT)res);
  540. return -1;
  541. }
  542. return 0;
  543. }
  544. /*
  545. wrapper structure to associate a dirent with a DIR
  546. */
  547. struct DIR_Wrapper {
  548. DIR d; // must be first structure element
  549. struct dirent de;
  550. };
  551. DIR *AP_Filesystem::opendir(const char *pathdir)
  552. {
  553. WITH_SEMAPHORE(sem);
  554. CHECK_REMOUNT_NULL();
  555. debug("Opendir %s", pathdir);
  556. struct DIR_Wrapper *ret = new DIR_Wrapper;
  557. if (!ret) {
  558. return nullptr;
  559. }
  560. int res = f_opendir(&ret->d, pathdir);
  561. if (res == FR_DISK_ERR && RETRY_ALLOWED()) {
  562. // one retry on disk error
  563. if (remount_file_system()) {
  564. res = f_opendir(&ret->d, pathdir);
  565. }
  566. }
  567. if (res != FR_OK) {
  568. errno = fatfs_to_errno((FRESULT)res);
  569. delete ret;
  570. return nullptr;
  571. }
  572. debug("Opendir %s -> %p", pathdir, ret);
  573. return &ret->d;
  574. }
  575. struct dirent *AP_Filesystem::readdir(DIR *dirp)
  576. {
  577. WITH_SEMAPHORE(sem);
  578. struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;
  579. if (!d) {
  580. errno = EINVAL;
  581. return nullptr;
  582. }
  583. FILINFO fno;
  584. int len;
  585. int res;
  586. d->de.d_name[0] = 0;
  587. res = f_readdir ( dirp, &fno );
  588. if (res != FR_OK || fno.fname[0] == 0) {
  589. errno = fatfs_to_errno((FRESULT)res);
  590. return nullptr;
  591. }
  592. len = strlen(fno.fname);
  593. strncpy(d->de.d_name,fno.fname,len);
  594. d->de.d_name[len] = 0;
  595. return &d->de;
  596. }
  597. int AP_Filesystem::closedir(DIR *dirp)
  598. {
  599. WITH_SEMAPHORE(sem);
  600. struct DIR_Wrapper *d = (struct DIR_Wrapper *)dirp;
  601. if (!d) {
  602. errno = EINVAL;
  603. return -1;
  604. }
  605. int res = f_closedir (dirp);
  606. delete d;
  607. if (res != FR_OK) {
  608. errno = fatfs_to_errno((FRESULT)res);
  609. return -1;
  610. }
  611. debug("closedir");
  612. return 0;
  613. }
  614. // return free disk space in bytes
  615. int64_t AP_Filesystem::disk_free(const char *path)
  616. {
  617. WITH_SEMAPHORE(sem);
  618. FATFS *fs;
  619. DWORD fre_clust, fre_sect;
  620. CHECK_REMOUNT();
  621. /* Get volume information and free clusters of drive 1 */
  622. FRESULT res = f_getfree("/", &fre_clust, &fs);
  623. if (res) {
  624. return res;
  625. }
  626. /* Get total sectors and free sectors */
  627. fre_sect = fre_clust * fs->csize;
  628. return (int64_t)(fre_sect)*512;
  629. }
  630. // return total disk space in bytes
  631. int64_t AP_Filesystem::disk_space(const char *path)
  632. {
  633. WITH_SEMAPHORE(sem);
  634. CHECK_REMOUNT();
  635. FATFS *fs;
  636. DWORD fre_clust, tot_sect;
  637. /* Get volume information and free clusters of drive 1 */
  638. FRESULT res = f_getfree("/", &fre_clust, &fs);
  639. if (res) {
  640. return -1;
  641. }
  642. /* Get total sectors and free sectors */
  643. tot_sect = (fs->n_fatent - 2) * fs->csize;
  644. return (int64_t)(tot_sect)*512;
  645. }
  646. /*
  647. convert unix time_t to FATFS timestamp
  648. */
  649. static void unix_time_to_fat(time_t epoch, uint16_t &date, uint16_t &time)
  650. {
  651. struct tm *t = gmtime((time_t *)&epoch);
  652. /* Pack date and time into a uint32_t variable */
  653. date = ((uint16_t)(t->tm_year - 80) << 9)
  654. | (((uint16_t)t->tm_mon+1) << 5)
  655. | (((uint16_t)t->tm_mday));
  656. time = ((uint16_t)t->tm_hour << 11)
  657. | ((uint16_t)t->tm_min << 5)
  658. | ((uint16_t)t->tm_sec >> 1);
  659. }
  660. /*
  661. set mtime on a file
  662. */
  663. bool AP_Filesystem::set_mtime(const char *filename, const time_t mtime_sec)
  664. {
  665. FILINFO fno;
  666. uint16_t fdate, ftime;
  667. unix_time_to_fat(mtime_sec, fdate, ftime);
  668. fno.fdate = fdate;
  669. fno.ftime = ftime;
  670. return f_utime(filename, (FILINFO *)&fno) == FR_OK;
  671. }
  672. /*
  673. convert POSIX errno to text with user message.
  674. */
  675. char *strerror(int errnum)
  676. {
  677. #define SWITCH_ERROR(errno) case errno: return const_cast<char *>(#errno); break
  678. switch (errnum) {
  679. SWITCH_ERROR(EPERM);
  680. SWITCH_ERROR(ENOENT);
  681. SWITCH_ERROR(ESRCH);
  682. SWITCH_ERROR(EINTR);
  683. SWITCH_ERROR(EIO);
  684. SWITCH_ERROR(ENXIO);
  685. SWITCH_ERROR(E2BIG);
  686. SWITCH_ERROR(ENOEXEC);
  687. SWITCH_ERROR(EBADF);
  688. SWITCH_ERROR(ECHILD);
  689. SWITCH_ERROR(EAGAIN);
  690. SWITCH_ERROR(ENOMEM);
  691. SWITCH_ERROR(EACCES);
  692. SWITCH_ERROR(EFAULT);
  693. #ifdef ENOTBLK
  694. SWITCH_ERROR(ENOTBLK);
  695. #endif // ENOTBLK
  696. SWITCH_ERROR(EBUSY);
  697. SWITCH_ERROR(EEXIST);
  698. SWITCH_ERROR(EXDEV);
  699. SWITCH_ERROR(ENODEV);
  700. SWITCH_ERROR(ENOTDIR);
  701. SWITCH_ERROR(EISDIR);
  702. SWITCH_ERROR(EINVAL);
  703. SWITCH_ERROR(ENFILE);
  704. SWITCH_ERROR(EMFILE);
  705. SWITCH_ERROR(ENOTTY);
  706. SWITCH_ERROR(ETXTBSY);
  707. SWITCH_ERROR(EFBIG);
  708. SWITCH_ERROR(ENOSPC);
  709. SWITCH_ERROR(ESPIPE);
  710. SWITCH_ERROR(EROFS);
  711. SWITCH_ERROR(EMLINK);
  712. SWITCH_ERROR(EPIPE);
  713. SWITCH_ERROR(EDOM);
  714. SWITCH_ERROR(ERANGE);
  715. SWITCH_ERROR(EBADMSG);
  716. }
  717. #undef SWITCH_ERROR
  718. return NULL;
  719. }
  720. #endif // CONFIG_HAL_BOARD