APM:Libraries
SD.cpp
Go to the documentation of this file.
1 /*
2  night_ghost@ykoctpa.ru 2017
3 
4  a port of SparkFun's SD class to FatFs (c) Chan
5  because it much better and faster than sdfatlib
6 
7  also it was rewritten to:
8 * distinguish between flie at directory by stat(), not by try to open
9 * provide last error code and its text description
10 * added tracking of opened files for global sync()
11 * some new functions added
12 * reduced memory usage by half
13 
14 
15  original SparkFun readme below
16 ----------------------------------------------
17 
18  SD - a slightly more friendly wrapper for sdfatlib
19 
20  This library aims to expose a subset of SD card functionality
21  in the form of a higher level "wrapper" object.
22 
23  License: GNU General Public License V3
24  (Because sdfatlib is licensed with this.)
25 
26  (C) Copyright 2010 SparkFun Electronics
27 
28 
29  This library provides four key benefits:
30 
31  * Including `SD.h` automatically creates a global
32  `SD` object which can be interacted with in a similar
33  manner to other standard global objects like `Serial` and `Ethernet`.
34 
35  * Boilerplate initialisation code is contained in one method named
36  `begin` and no further objects need to be created in order to access
37  the SD card.
38 
39  * Calls to `open` can supply a full path name including parent
40  directories which simplifies interacting with files in subdirectories.
41 
42  * Utility methods are provided to determine whether a file exists
43  and to create a directory heirarchy.
44 
45 
46  Note however that not all functionality provided by the underlying
47  sdfatlib library is exposed.
48 
49  */
50 
51 
52 extern "C" {
53  #include <stdlib.h>
54  #include <string.h>
55  #include <inttypes.h>
56 }
57 
58 #include "assert.h"
59 #include <utility>
60 #include "SD.h"
61 
62 #if defined(BOARD_SDCARD_CS_PIN) || defined(BOARD_DATAFLASH_FATFS)
63 
64 SDClass SD;
65 
66 Sd2Card SDClass::_card;
67 SdFatFs SDClass::_fatFs;
68 
69 FRESULT SDClass::lastError = FR_OK;
70 
77 uint8_t SDClass::begin(AP_HAL::OwnPtr<F4Light::SPIDevice> spi)
78 {
79  if (_card.init(std::move(spi))) {
80  lastError=_fatFs.init(&_card);
81  if(lastError == FR_OK) return true;
82  printf("\nSD card error: %s\n", strError(lastError));
83  return false;
84  }
85  printf("\nSD card init error!\n");
86  return FALSE;
87 }
88 
89 
95 uint8_t SDClass::exists(const char *filepath)
96 {
97  FILINFO fno;
98 
99  lastError=f_stat(filepath, &fno);
100 
101  // FatFs gives such error for root directory
102  return lastError == FR_OK || lastError == FR_INVALID_NAME;
103 }
104 
110 uint8_t SDClass::mkdir(const char *filepath)
111 {
112  lastError = f_mkdir(filepath);
113  return lastError == FR_OK;
114 }
115 
121 uint8_t SDClass::rmdir(const char *filepath)
122 {
123  lastError = f_unlink(filepath);
124  return lastError == FR_OK;
125 }
126 
132 File SDClass::open(const char *filepath)
133 {
134  File file = File(filepath);
135 
136  FILINFO fno;
137 
138  lastError=f_stat(filepath, &fno);
139 
140  if(lastError!=FR_OK){ // no file
141  return file;
142  }
143 
144  if(fno.fattrib & AM_DIR) {
145  lastError = f_opendir(&file._d.dir, filepath);
146  file.is_dir=true;
147  if( lastError != FR_OK) {
148  file.close();
149  }
150  } else {
151  lastError = f_open(&file._d.fil, filepath, FA_READ);
152  file.is_dir=false;
153 
154  if( lastError == FR_OK) {
155  File::addOpenFile(&file._d.fil);
156  } else {
157  file.close();
158  }
159  }
160  return file;
161 }
162 
169 File SDClass::open(const char *filepath, uint8_t mode)
170 {
171  File file = File(filepath);
172 
173  FILINFO fno;
174 
175  lastError=f_stat(filepath, &fno);
176 
177  if(lastError == FR_OK && fno.fattrib & AM_DIR) { // exists and is dir
178  if(!(mode & FILE_WRITE)){
179  lastError = f_opendir(&file._d.dir, filepath);
180  file.is_dir=true;
181  } else {
182  lastError = FR_IS_DIR;
183  }
184  if( lastError != FR_OK) file.close();
185  } else { // dir not exists - regular file
186 
187  if((mode & FILE_WRITE) && lastError==FR_OK) { // the modes of opening the file are different. if a file exists
188  mode &= ~FA_CREATE_NEW; // then remove the creation flag - or we will got error "file exists"
189  }
190 
191  lastError = f_open(&file._d.fil, filepath, mode);
192  file.is_dir=false;
193 
194  if( lastError == FR_OK){
195  if(mode & O_APPEND){
196  f_lseek(&file._d.fil, f_size(&file._d.fil));
197  }
198  File::addOpenFile(&file._d.fil);
199  } else {
200  file.close();
201  }
202  }
203  return file;
204 }
205 
211 uint8_t SDClass::remove(const char *filepath)
212 {
213  lastError = f_unlink(filepath);
214  return lastError == FR_OK;
215 }
216 
217 File SDClass::openRoot(void)
218 {
219  File file = File(_fatFs.getRoot());
220 
221  lastError = f_opendir(&file._d.dir, _fatFs.getRoot());
222  file.is_dir = true;
223  if(lastError != FR_OK) {
224  file._d.dir.obj.fs = 0;
225  }
226  return file;
227 }
228 
229 
230 
231 uint32_t SDClass::getfree(const char *filepath, uint32_t * fssize){
232  FATFS *fs;
233  DWORD fre_clust, fre_sect;
234 
235 
236  /* Get volume information and free clusters of drive */
237  lastError = f_getfree(filepath, &fre_clust, &fs);
238  if (lastError != FR_OK) return -1;
239 
240  /* Get total sectors and free sectors */
241  if(fssize) *fssize = (fs->n_fatent - 2) * fs->csize; // tot_sect
242  fre_sect = fre_clust * fs->csize;
243 
244  return fre_sect;
245 }
246 
247 
248 //f_stat ( const TCHAR* path, /* Pointer to the file path */ FILINFO* fno )
249 uint8_t SDClass::stat(const char *filepath, FILINFO* fno){
250  lastError = f_stat(filepath, fno);
251  if(lastError != FR_OK) return -1;
252  return 0;
253 }
254 
255 uint8_t SDClass::format(const char *filepath){
256 
257  lastError = _fatFs.format(filepath, &_card);
258 
259  return lastError == FR_OK;
260 }
261 
262 
263 
264 //* *************************************
265 File::File()
266 {
267  _name = NULL;
268  _d.fil.obj.fs = 0;
269  _d.dir.obj.fs = 0;
270 }
271 
272 File::File(const char* fname)
273 {
274  _name = (char*)malloc(strlen(fname) +1);
275 
276  //assert(_name != NULL );
277  if(_name == NULL) return; // no HardFault, just not opened
278 
279  strcpy(_name, fname);
280  _d.fil.obj.fs = 0;
281  _d.dir.obj.fs = 0;
282 }
283 
297 void File::ls(cb_putc cb, uint8_t flags, uint8_t indent) {
298  FRESULT res = FR_OK;
299  FILINFO fno;
300  char *fn;
301 
302  if(!is_dir) return;
303 
304 #if _USE_LFN
305  static char lfn[_MAX_LFN];
306  fno.lfname = lfn;
307  fno.lfsize = sizeof(lfn);
308 #endif
309 
310  while(1) {
311  res = f_readdir(&_d.dir, &fno);
312  if(res != FR_OK || fno.fname[0] == 0) {
313  break;
314  }
315  if(fno.fname[0] == '.') {
316  continue;
317  }
318 #if _USE_LFN
319  fn = *fno.lfname ? fno.lfname : fno.fname;
320 #else
321  fn = fno.fname;
322 #endif
323  //print any indent spaces
324  for (int8_t i = 0; i < indent; i++) cb(' ');
325  printStr(fn, cb);
326 
327  if((fno.fattrib & AM_DIR) == 0) {
328  // print modify date/time if requested
329  if (flags & LS_DATE) {
330  cb(' ');
331  printFatDate(fno.fdate,cb);
332  cb(' ');
333  printFatTime(fno.ftime,cb);
334  }
335  // print size if requested
336  if (flags & LS_SIZE) {
337  cb(' ');
338  printNumber(fno.fsize, cb);
339  }
340  cb('\r'); cb('\n');
341  }
342  else
343  {
344  // list subdirectory content if requested
345  if (flags & LS_R)
346  {
347  char *fullPath;
348  fullPath = (char*)malloc(strlen(_name) + 1 + strlen(fn) +1);
349  if (fullPath != NULL) {
350  sprintf(fullPath, "%s/%s", _name, fn);
351  File filtmp = SD.open(fullPath);
352 
353  if (filtmp._name != NULL) {
354  cb('\r'); cb('\n');
355  filtmp.ls(cb,flags, indent+2);
356  filtmp.close();
357  } else {
358  printStr(fn, cb);
359  cb('\r'); cb('\n');
360 
361  static const char err_s[] = "Error to open dir: ";
362  printStr(err_s, cb);
363  printStr(fn, cb);
364  }
365  free(fullPath);
366  } else {
367  cb('\r'); cb('\n');
368  static const char err_s[] = "Error to allocate memory!";
369  printStr(err_s, cb);
370  }
371  }
372  }
373  }
374 }
375 //------------------------------------------------------------------------------
382 void File::printFatDate(uint16_t fatDate, cb_putc cb) {
383  printNumber(FAT_YEAR(fatDate), cb);
384  cb('-');
385  printTwoDigits(FAT_MONTH(fatDate),cb);
386  cb('-');
387  printTwoDigits(FAT_DAY(fatDate),cb);
388 }
389 //------------------------------------------------------------------------------
396 void File::printFatTime(uint16_t fatTime, cb_putc cb) {
397  printTwoDigits(FAT_HOUR(fatTime), cb);
398  cb(':');
399  printTwoDigits(FAT_MINUTE(fatTime), cb);
400  cb(':');
401  printTwoDigits(FAT_SECOND(fatTime), cb);
402 }
403 //------------------------------------------------------------------------------
408 void File::printTwoDigits(uint8_t v, cb_putc cb) {
409  cb('0' + v/10);
410  cb('0' + v % 10);
411 }
412 
413 void File::printNumber(int16_t n, cb_putc cb) {
414  const uint8_t base = 10;
415 
416  if (n < 0) {
417  cb('-');
418  n = -n;
419  }
420 
421  char buf[8 * sizeof(long) + 1]; // Assumes 8-bit chars plus zero byte.
422  char *str = &buf[sizeof(buf) - 1];
423 
424  *str = '\0';
425 
426  do {
427  char c = n % base;
428  n /= base;
429 
430  *--str = c < 10 ? c + '0' : c + 'A' - 10;
431  } while(n);
432 
433  printStr(str, cb);
434 }
435 
436 void File::printStr(const char *s, cb_putc cb) {
437  while(*s) cb(*s++);
438 }
439 
440 
445 int File::read()
446 {
447  UINT byteread;
448  int8_t data;
449  SD.lastError = f_read(&_d.fil, (void *)&data, 1, &byteread);
450  return data;
451 }
452 
459 int File::read(void* buf, size_t len)
460 {
461  UINT bytesread;
462 
463  SD.lastError = f_read(&_d.fil, buf, len, &bytesread);
464  return bytesread;
465 
466 }
467 
468 UINT File::gets(char* buf, size_t len)
469 {
470  UINT bytesread=0;
471 
472  while(len--){
473 
474  uint8_t c;
475  uint8_t ret = read(&c,1);
476  if(!ret) break; // EOF
477  if(c=='\n') break;
478  if(c=='\r') continue;
479  *buf++=c;
480  *buf=0; // close string
481  bytesread++;
482  }
483  return bytesread;
484 
485 }
486 
492 void File::close()
493 {
494  if(_name){
495  if(is_dir) {
496  if(_d.dir.obj.fs != 0) {
497  SD.lastError = f_closedir(&_d.dir);
498  }
499  } else {
500  if(_d.fil.obj.fs != 0) {
501  /* Flush the file before close */
502  f_sync(&_d.fil);
503 
504  /* Close the file */
505  SD.lastError = f_close(&_d.fil);
506  }
507 
508  removeOpenFile(&_d.fil);
509  free(_name);
510  _name=NULL;
511  }
512  }
513 }
514 
515 
521 void File::flush()
522 {
523  if(!is_dir) {
524  SD.lastError = f_sync(&_d.fil);
525  }
526 }
527 
533 int File::peek()
534 {
535  int data;
536  data = read();
537  seek(position() -1);
538  return data;
539 }
540 
546 uint32_t File::position()
547 {
548  return f_tell(&_d.fil);
549 }
550 
556 uint8_t File::seek(uint32_t pos)
557 {
558  if(is_dir) return false;
559 
560  if(pos > size()) {
561  return FALSE;
562  } else {
563  SD.lastError = f_lseek(&_d.fil, pos);
564  return SD.lastError == FR_OK;
565  }
566 }
567 
573 uint32_t File::size()
574 {
575  if(is_dir) return 0;
576  return f_size(&_d.fil);
577 }
578 
579 
585 size_t File::write(uint8_t data)
586 {
587  return write(&data, 1);
588 }
589 
596 size_t File::write(const char *buf, size_t sz)
597 {
598  size_t byteswritten;
599  if(is_dir) return 0;
600 
601  SD.lastError = f_write(&_d.fil, (const void *)buf, sz, (UINT *)&byteswritten);
602  return byteswritten;
603 }
604 
605 size_t File::write(const uint8_t *buf, size_t sz)
606 {
607  return write((const char *)buf, sz);
608 }
609 
615 size_t File::print(const char* data)
616 {
617  return write(data, strlen(data));
618 }
619 
624 size_t File::println()
625 {
626  return write("\r\n", 2);
627 }
628 
634 size_t File::println(const char* data)
635 {
636  size_t bytewritten = write(data, strlen(data));
637  bytewritten += println();
638  return bytewritten;
639 }
640 
641 
646 int File::available()
647 {
648  uint32_t n = size() - position();
649  return n > 0x7FFF ? 0x7FFF : n;
650 }
651 
652 
653 char* File::name()
654 {
655  char *fname = strrchr(_name, '/');
656  if (fname && fname[0] == '/')
657  fname++;
658  return fname;
659 }
660 
665 uint8_t File::isDirectory()
666 {
667  //assert(_name != NULL );
668 
669  if(_name == NULL) return false;
670 
671 
672  if (is_dir){
673  if(_d.dir.obj.fs != 0) return TRUE;
674  } else {
675  if(_d.fil.obj.fs != 0) return FALSE;
676  }
677 
678  // if not init get info
679  FILINFO fno;
680 
681  SD.lastError = f_stat(_name, &fno);
682  if (SD.lastError == FR_OK) {
683  if(fno.fattrib & AM_DIR){
684  is_dir = true;
685  return TRUE;
686  } else {
687  is_dir=false;
688  return FALSE;
689  }
690  }
691 
692  return FALSE;
693 }
694 
695 
696 // TODO: some strange and not works at all
697 File File::openNextFile(uint8_t mode)
698 {
699  if(!is_dir) return File();
700 
701  FRESULT res = FR_OK;
702  FILINFO fno;
703  char *fn;
704  char *fullPath = NULL;
705  size_t name_len= strlen(_name);
706  size_t len = name_len;
707 #if _USE_LFN
708  static char lfn[_MAX_LFN];
709  fno.lfname = lfn;
710  fno.lfsize = sizeof(lfn);
711 #endif
712  while(1) {
713  res = f_readdir(&_d.dir, &fno);
714  if(res != FR_OK || fno.fname[0] == 0) {
715  return File();
716  }
717  if(fno.fname[0] == '.') {
718  continue;
719  }
720 #if _USE_LFN
721  fn = *fno.lfname ? fno.lfname : fno.fname;
722 #else
723  fn = fno.fname;
724 #endif
725  len += strlen(fn) +2;
726  fullPath = (char*)malloc(len);
727  if (fullPath != NULL) {
728  // Avoid twice '/'
729  if ((name_len > 0) && (_name[name_len-1] == '/')) {
730  sprintf(fullPath, "%s%s", _name, fn);
731  } else {
732  sprintf(fullPath, "%s/%s", _name, fn);
733  }
734  File filtmp = SD.open(fullPath, mode);
735  free(fullPath);
736  return filtmp;
737  } else {
738  return File();
739  }
740  }
741 }
742 
743 void File::rewindDirectory(void)
744 {
745  if(isDirectory()) {
746  if(_d.dir.obj.fs != 0) {
747  f_closedir(&_d.dir);
748  }
749  f_opendir(&_d.dir, _name);
750  }
751 }
752 
753 #define MAX_OPEN_FILES 16
754 FIL* File::openFiles[MAX_OPEN_FILES]= {0};
755 uint8_t File::num_openFiles=0;
756 
757 void File::syncAll(){
758  for(uint8_t i=0; i<num_openFiles;i++){
759  if(openFiles[i])
760  f_sync(openFiles[i]);
761  }
762 }
763 
764 void File::addOpenFile(FIL *f){
765  for(uint8_t i=0; i<num_openFiles;i++){
766  if(!openFiles[i]) {
767  openFiles[i] = f;
768  return;
769  }
770  }
771  if(num_openFiles<MAX_OPEN_FILES){
772  openFiles[num_openFiles++] = f;
773  }
774 }
775 
776 void File::removeOpenFile(FIL *f){
777  for(uint8_t i=0; i<num_openFiles;i++){
778  if(openFiles[i] == f) {
779  openFiles[i] = NULL;
780  return;
781  }
782  }
783 }
784 
785 #endif
TCHAR fname[12+1]
Definition: ff.h:235
int printf(const char *fmt,...)
Definition: stdio.c:113
DWORD n_fatent
Definition: ff.h:137
FRESULT f_closedir(DIR *dp)
Definition: ff.c:4467
void(* cb_putc)(uint8_t c)
Definition: prototypes.h:3
FRESULT f_lseek(FIL *fp, FSIZE_t ofs)
Definition: ff.c:4240
WORD fdate
Definition: ff.h:228
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
#define FA_CREATE_NEW
Definition: ff.h:362
Definition: ff.h:226
FRESULT f_unlink(const TCHAR *path)
Definition: ff.c:4759
FRESULT f_close(FIL *fp)
Definition: ff.c:4026
int remove(const char *pathname)
Definition: posix.c:1706
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
Definition: ff.h:99
#define _MAX_LFN
Definition: ffconf.h:107
WORD ftime
Definition: ff.h:229
#define f_tell(fp)
Definition: ff.h:310
int rmdir(const char *pathname)
POSIX delete a directory.
Definition: posix.c:1671
const char * name
Definition: BusTest.cpp:11
#define FA_READ
Definition: ff.h:359
unsigned long DWORD
Definition: integer.h:22
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
FRESULT f_readdir(DIR *dp, FILINFO *fno)
Definition: ff.c:4497
FRESULT f_read(FIL *fp, void *buff, UINT btr, UINT *br)
Definition: ff.c:3721
FRESULT f_getfree(const TCHAR *path, DWORD *nclst, FATFS **fatfs)
Definition: ff.c:4620
#define f(i)
FRESULT f_sync(FIL *fp)
Definition: ff.c:3945
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
FRESULT
Definition: ff.h:243
FRESULT f_stat(const TCHAR *path, FILINFO *fno)
Definition: ff.c:4585
Definition: ff.h:264
FSIZE_t fsize
Definition: ff.h:227
float v
Definition: Printf.cpp:15
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Definition: posix.c:1620
char * gets(char *p)
Definition: posix.c:429
void * malloc(size_t size)
Definition: malloc.c:61
#define NULL
Definition: hal_types.h:59
void free(void *ptr)
Definition: malloc.c:81
FRESULT f_opendir(DIR *dp, const TCHAR *path)
Definition: ff.c:4401
static int is_dir(const char *path)
Definition: Storage.cpp:27
BYTE fattrib
Definition: ff.h:230
unsigned int UINT
Definition: integer.h:10
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
#define f_size(fp)
Definition: ff.h:311
Definition: ff.h:173
FRESULT f_mkdir(const TCHAR *path)
Definition: ff.c:4853
Definition: ff.h:244
#define AM_DIR
Definition: ff.h:387
FRESULT f_write(FIL *fp, const void *buff, UINT btw, UINT *bw)
Definition: ff.c:3821
FRESULT f_open(FIL *fp, const TCHAR *path, BYTE mode)
Definition: ff.c:3530
WORD csize
Definition: ff.h:112