APM:Libraries
Sd2Card.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 
5  a low-level interface for SD card driver
6 
7 */
8 #pragma GCC optimize ("O2")
9 
10 #include "Sd2Card.h"
11 #include "SdFatFs.h"
12 #include <stdio.h>
13 #include <util.h>
14 #include <utility>
15 
16 #include <systick.h>
17 #include <hal.h>
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <GCS_MAVLink/GCS.h>
21 
22 #if defined(BOARD_SDCARD_CS_PIN) || defined(BOARD_DATAFLASH_FATFS)
23 
27 
28 
29 using namespace F4Light;
30 
31 extern const AP_HAL::HAL& hal;
32 
34 AP_HAL::Semaphore *_spi_sem;
35 static AP_HAL::Device::Speed _speed;
36 
37 
39 void spi_spiSend(uint8_t b) {
40  return _spi->send(b);
41 }
42 
44 uint8_t spi_spiRecv(void) {
45  return _spi->transfer(0xFF);
46 }
47 
48 uint8_t spi_spiXchg(uint8_t b) {
49  return _spi->transfer(b);
50 }
51 
52 uint8_t spi_waitFor(uint8_t out, spi_WaitFunc cb, uint32_t dly) {
53  return _spi->wait_for(out, cb, dly);
54 }
55 
56 void spi_spiTransfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) {
57  _spi->transfer(send, send_len, recv, recv_len);
58 }
59 
60 //------------------------------------------------------------------------------
61 
62 
63 void spi_yield(){
64  hal_yield(0); // while we wait - let others work
65 }
66 
67 
68 uint8_t spi_detect(){
69 #ifdef BOARD_SDCARD_DET_PIN
71  return gpio_read_bit(pp.gpio_device, pp.gpio_bit) == LOW;
72 #else
73  return 1;
74 #endif
75 }
76 
77 
78 
79 
80 
81 
82 uint32_t get_fattime()
83 {
84  uint64_t now = hal.util->get_system_clock_ms(); //millis + gps_time_shift
85 
86  uint16_t year = 1970;
87  uint8_t month;
88 
89  uint64_t seconds = now / 1000;
90  uint32_t sys_days = seconds / (24*60*60uL);
91  uint16_t day_seconds = seconds % (24*60*60uL);
92 
93  uint32_t days = sys_days;
94  uint16_t y_day;
95 
96  while(1) {
97  bool leapYear = (year % 4 == 0 && (year % 100 != 0 || year % 400 == 0));
98  uint16_t daysInYear = leapYear ? 366 : 365;
99 
100  if (days >= daysInYear) {
101  days -= daysInYear;
102  ++year;
103  } else {
104  y_day = days;
105 
106  /* calculate the month and day */
107  static const uint8_t daysInMonth[12] = {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31};
108  for(month = 0; month < 12; ++month) {
109  uint8_t dim = daysInMonth[month];
110 
111  /* add a day to feburary if this is a leap year */
112  if (month == 1 && leapYear) ++dim;
113 
114  if (days >= dim)
115  days -= dim;
116  else
117  break;
118  }
119  break;
120  }
121  }
122 
123  uint16_t min = day_seconds / 60;
124  uint16_t hour = min /60;
125 
126  uint16_t sec = day_seconds % 60;
127 
128 
129  /* Pack date and time into a uint32_t variable */
130  return ((uint32_t)(year - 1980) << 25)
131  | ((uint32_t)month << 21)
132  | ((uint32_t)days << 16)
133  | ((uint32_t)hour << 11)
134  | ((uint32_t)min << 5)
135  | ((uint32_t)sec >> 1);
136 }
137 
138 #endif
139 
140 
141 #if defined(BOARD_SDCARD_CS_PIN)
142 
143 void spi_chipSelectHigh(void) {
144  _spi->wait_busy();
147  _spi_sem->give();
148 }
149 
150 bool spi_chipSelectLow(bool take_sem) {
151  if(take_sem){
152  if(!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) return false;
153 
154  _spi->set_speed(_speed);
155 
156  }
159  return true;
160 }
161 
162 
164 
165  _spi = std::move(spi);
166 
167 
168  // set pin modes
169  {
174  }
175 
176 #ifdef BOARD_SDCARD_DET_PIN
177  {
181  }
182 #endif
183 
184  _spi_sem = _spi->get_semaphore();
185 
186  if(!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) return false;
187 
188  //_spi->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&Sd2Card::_timer, void));
189  Revo_handler h = { .mp = FUNCTOR_BIND_MEMBER(&Sd2Card::_timer, void) };
191 
192  _speed = AP_HAL::Device::SPEED_LOW; // all initialization at low speed
193  _spi->set_speed(_speed);
194 
195  // must supply min of 74 clock cycles with CS high.
196  for (uint8_t i = 0; i < 10; i++) spi_spiSend(0XFF);
197 
198  _spi_sem->give();
199 
200  uint8_t n_try=3;
201 
202  DSTATUS ret;
203  do {
204  ret = disk_initialize(0);
205  } while(ret!=RES_OK && n_try-- != 0);
206 
207  printf("\nSD initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL);
208  gcs().send_text(MAV_SEVERITY_INFO, "\nSD initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL);
209 
211 
212  return ret == RES_OK;
213 }
214 
215 #elif defined(BOARD_DATAFLASH_FATFS)
216 
217 #define DF_RESET BOARD_DATAFLASH_CS_PIN
218 
219 void spi_chipSelectHigh(void) {
220  _spi->wait_busy();
223  _spi_sem->give();
224 }
225 
226 bool spi_chipSelectLow(bool take_sem) {
227  if(take_sem){
228  if(!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) return false;
229 
230  _spi->set_speed(_speed);
231 
232  }
235  return true;
236 }
237 
239 
240  _spi = std::move(spi);
241 
244  // Reset the chip. We don't need a semaphore because no SPI activity
248 
249  if (!_spi) {
250  printf("DataFlash SPIDeviceDriver not found\n");
251  return false;
252  }
253 
254  _spi_sem = _spi->get_semaphore();
255  if (!_spi_sem) {
256  printf("DataFlash SPIDeviceDriver semaphore is null\n");
257  return false;
258  }
259 
260  if(!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) return false; // just for check
261 
262  _spi_sem->give();
263 
264  Revo_handler h = { .mp = FUNCTOR_BIND_MEMBER(&Sd2Card::_timer, void) };
265  systick_attach_callback(h.h); // not at common interrupt level as tasks because it can be called at USB interrupt level.
266  // Systick has own interrupt level above all IRQ
267 
269 
270  DSTATUS ret;
271  ret = disk_initialize(0);
272 
273  printf("\nDataFlash initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL);
274  gcs().send_text(MAV_SEVERITY_INFO, "\nDataFlash initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL);
275 
276  return ret == RES_OK;
277 }
278 
279 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_HAL::MemberProc mp
Definition: handler.h:18
uint8_t spi_detect()
#define BOARD_SDCARD_CS_PIN
Definition: board.h:137
F4Light::Semaphore * get_semaphore()
Definition: SPIDevice.h:143
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
Handler h
Definition: handler.h:20
void send(uint8_t out)
Definition: SPIDevice.cpp:178
Interface definition for the various Ground Control System.
void systick_attach_callback(Handler callback)
Attach a callback to be called from the SysTick exception handler.
Definition: systick.c:28
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
Definition: GPIO.h:35
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
GCS & gcs()
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define DF_RESET
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 BOARD_DATAFLASH_CS_PIN
Definition: board.h:66
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
#define HIGH
Definition: board.h:34
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:742
BYTE DSTATUS
Definition: diskio.h:17
static void _setSpeed(uint8_t pin, GPIOSpeed_t gpio_speed)
Definition: GPIO.h:168
uint8_t spi_waitFor(uint8_t out, spi_WaitFunc cb, uint32_t dly)
bool spi_chipSelectLow(bool take_sem)
Definition: diskio.h:21
uint8_t spi_spiRecv(void)
Miscellaneous utility macros and procedures.
#define LOW
Definition: board.h:31
virtual bool give()=0
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
DSTATUS disk_initialize(BYTE pdrv)
Definition: diskio.c:49
void spi_chipSelectHigh(void)
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:188
uint8_t spi_spiSend(uint8_t b)
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
Definition: gpio_hal.h:130
static void _delay(uint16_t ms)
Definition: Scheduler.cpp:258
void init()
Generic board initialization function.
Definition: system.cpp:136
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
Definition: gpio_hal.h:161
uint32_t get_fattime()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void spi_spiTransfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)
uint64_t get_system_clock_ms() const
Definition: Util.cpp:63
uint8_t spi_spiXchg(uint8_t b)
uint8_t gpio_bit
Definition: boards.h:92
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
uint8_t wait_for(uint8_t out, spi_WaitFunc cb, uint32_t dly)
Definition: SPIDevice.cpp:875
const gpio_dev *const gpio_device
Definition: boards.h:89
#define BOARD_SDCARD_DET_PIN
Definition: board.h:138
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
void spi_yield()
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115