8 #pragma GCC optimize ("O2")    22 #if defined(BOARD_SDCARD_CS_PIN) || defined(BOARD_DATAFLASH_FATFS)    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);
    69 #ifdef  BOARD_SDCARD_DET_PIN    89     uint64_t seconds = now / 1000;
    90     uint32_t sys_days    = seconds / (24*60*60uL);
    91     uint16_t day_seconds = seconds % (24*60*60uL);
    93     uint32_t days = sys_days;
    97         bool     leapYear   = (year % 4 == 0 && (year % 100 != 0 || year % 400 == 0));
    98         uint16_t daysInYear = leapYear ? 366 : 365;
   100         if (days >= daysInYear)  {
   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];
   112             if (month == 1 && leapYear)      ++dim;
   123     uint16_t min = day_seconds / 60;
   124     uint16_t hour = min /60;
   126     uint16_t sec = day_seconds % 60;
   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);
   141 #if defined(BOARD_SDCARD_CS_PIN)   165     _spi = std::move(spi);
   176 #ifdef BOARD_SDCARD_DET_PIN   196     for (uint8_t i = 0; i < 10; i++) 
spi_spiSend(0XFF);
   205     } 
while(ret!=
RES_OK && n_try-- != 0);
   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);
   215 #elif defined(BOARD_DATAFLASH_FATFS)   217 #define DF_RESET BOARD_DATAFLASH_CS_PIN   240     _spi = std::move(spi);
   250         printf(
"DataFlash SPIDeviceDriver not found\n");
   256         printf(
"DataFlash SPIDeviceDriver semaphore is null\n");
   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);
 int printf(const char *fmt,...)
 
#define BOARD_SDCARD_CS_PIN
 
F4Light::Semaphore * get_semaphore()
 
static void _pinMode(uint8_t pin, uint8_t output)
 
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. 
 
static void _write(uint8_t pin, uint8_t value)
 
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
 
#define HAL_SEMAPHORE_BLOCK_FOREVER
 
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
 
uint8_t(* spi_WaitFunc)(uint8_t b)
 
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- 
 
#define BOARD_DATAFLASH_CS_PIN
 
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
 
bool set_speed(AP_HAL::Device::Speed speed) override
 
static void _setSpeed(uint8_t pin, GPIOSpeed_t gpio_speed)
 
uint8_t spi_waitFor(uint8_t out, spi_WaitFunc cb, uint32_t dly)
 
bool spi_chipSelectLow(bool take_sem)
 
uint8_t spi_spiRecv(void)
 
Miscellaneous utility macros and procedures. 
 
void send_text(MAV_SEVERITY severity, const char *fmt,...)
 
DSTATUS disk_initialize(BYTE pdrv)
 
void spi_chipSelectHigh(void)
 
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
 
uint8_t spi_spiSend(uint8_t b)
 
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
 
static void _delay(uint16_t ms)
 
void init()
Generic board initialization function. 
 
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
 
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
 
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
 
uint8_t spi_spiXchg(uint8_t b)
 
Stores STM32-specific information related to a given Maple pin. 
 
uint8_t wait_for(uint8_t out, spi_WaitFunc cb, uint32_t dly)
 
const gpio_dev *const gpio_device
 
#define BOARD_SDCARD_DET_PIN
 
void hal_yield(uint16_t ttw)
 
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)