APM:Libraries
Sd2Card.h
Go to the documentation of this file.
1 /*
2 
3  a low-level interface for SD card driver
4 
5  */
6 #ifndef Sd2Card_h
7 #define Sd2Card_h
8 
9 #include "FatFs/drivers/sd.h"
10 #include "FatFs/diskio.h"
11 
12 #include <AP_HAL/AP_HAL.h>
13 
14 
15 #if defined(BOARD_SDCARD_CS_PIN) || defined(BOARD_DATAFLASH_FATFS)
16 
20 #include <AP_HAL_F4Light/handler.h>
21 
22 #include "FatFs/diskio.h"
23 
24 using namespace F4Light;
25 
26 #define FALSE ((uint8_t)0x00)
27 #define TRUE ((uint8_t)0x01)
28 
29 // card types to match Arduino definition
31 #define SD_CARD_TYPE_SD1 CT_SD1
32 
33 #define SD_CARD_TYPE_SD2 CT_SD2
34 
35 #define SD_CARD_TYPE_SDHC CT_BLOCK
36 
37 
38 
39 
40 extern "C" {
41  void spi_spiSend(uint8_t b);
42  uint8_t spi_spiRecv(void);
43  uint8_t spi_spiXchg(uint8_t b);
44  void spi_spiTransfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len);
45  void spi_chipSelectHigh(void);
46  bool spi_chipSelectLow(bool take_sem);
47  void spi_yield();
48  uint8_t spi_waitFor(uint8_t out, spi_WaitFunc cb, uint32_t dly);
49  uint8_t spi_detect();
50  uint32_t get_fattime();
51 };
52 
53 
54 class Sd2Card {
55 public:
56 
58 
60  static uint8_t type(void) { return sd_get_type(); }
61 
62  static uint16_t errorCode() { return sd_status(); }
63  static uint8_t writeBlock(uint8_t *buff, uint32_t block) { return sd_write(buff, block, 1)==RES_OK; }
64  static uint8_t readBlock(uint8_t *buff, uint32_t block){ return sd_read( buff, block, 1)==RES_OK; }
65 
66  static uint8_t writeBlock(uint8_t *buff, uint32_t block, uint16_t len) { return sd_write(buff, block, len)==RES_OK; }
67  static uint8_t readBlock(uint8_t *buff, uint32_t block, uint16_t len){ return sd_read( buff, block, len)==RES_OK; }
68 
69  static uint8_t ioctl(uint32_t cmd, uint32_t *buff){ return sd_ioctl(cmd, buff) == RES_OK; }
70 
71  static uint32_t sectorCount() { // full number of sectors
72  uint32_t sz;
73  if(sd_ioctl(GET_SECTOR_COUNT, &sz) == RES_OK)
74  return sz;
75  return 0;
76 
77  }
78 
79  static uint32_t blockSize() { // sectors in erase block
80  uint32_t sz;
81  if(sd_ioctl(GET_BLOCK_SIZE, &sz) == RES_OK)
82  return sz;
83 #ifdef BOARD_DATAFLASH_ERASE_SIZE
84  return BOARD_DATAFLASH_ERASE_SIZE/512;
85 #else
86  return 8;
87 #endif
88 
89  }
90 
91  static uint32_t sectorSize() { // sector size in bytes
92  uint32_t sz;
93  if(sd_ioctl(GET_SECTOR_SIZE, &sz) == RES_OK)
94  return sz;
95 
96  return 512;
97  }
98 
99 private:
100  void _timer(void) { sd_timerproc(); }
101 
102 };
103 
104 #endif // revomini
105 
106 #endif // sd2Card_h
#define GET_BLOCK_SIZE
Definition: diskio.h:53
uint8_t spi_detect()
DRESULT sd_write(const uint8_t *buff, uint32_t sector, uint16_t count)
DRESULT sd_read(uint8_t *buff, uint32_t sector, uint16_t count)
uint8_t(* spi_WaitFunc)(uint8_t b)
Definition: SPIDevice.h:48
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define GET_SECTOR_COUNT
Definition: diskio.h:51
#define BOARD_DATAFLASH_ERASE_SIZE
Definition: board.h:139
DRESULT sd_ioctl(uint8_t cmd, void *buff)
DSTATUS sd_status()
uint8_t spi_waitFor(uint8_t out, spi_WaitFunc cb, uint32_t dly)
void sd_timerproc()
bool spi_chipSelectLow(bool take_sem)
Definition: diskio.h:21
uint8_t spi_spiRecv(void)
uint8_t sd_get_type()
void spi_chipSelectHigh(void)
uint8_t spi_spiSend(uint8_t b)
#define GET_SECTOR_SIZE
Definition: diskio.h:52
void init()
Generic board initialization function.
Definition: system.cpp:136
uint32_t get_fattime()
void spi_spiTransfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)
uint8_t spi_spiXchg(uint8_t b)
void spi_yield()