96 typedef struct SPI_TRANS {
110 #define SPI_LOG_SIZE 200 123 bool transfer(
const uint8_t *send, uint32_t send_len,
124 uint8_t *recv, uint32_t recv_len)
override;
127 uint8_t transfer(uint8_t out);
128 void send(uint8_t out);
131 bool transfer_fullduplex(
const uint8_t *send, uint8_t *recv, uint32_t len)
override;
138 uint16_t send_strobe(
const uint8_t *
buffer, uint16_t len);
140 uint8_t wait_for(uint8_t out,
spi_WaitFunc cb, uint32_t dly);
158 void register_completion_callback(
Handler h);
162 register_completion_callback(r.
h);
167 register_completion_callback(r.
h);
173 #define SPI_BUFFER_SIZE 512 // one SD-card sector 197 uint8_t _transfer(uint8_t data);
199 void get_dma_ready();
201 void setup_dma_transfer(
const uint8_t *send,
const uint8_t *recv, uint32_t btr );
202 void setup_isr_transfer();
204 void start_dma_transfer();
205 uint8_t do_transfer(
bool is_DMA, uint32_t nbytes);
222 void isr_transfer_finish();
225 #ifdef BOARD_SOFTWARE_SPI 226 volatile GPIO_TypeDef *sck_port;
229 volatile GPIO_TypeDef *mosi_port;
232 volatile GPIO_TypeDef *miso_port;
236 void spi_soft_set_speed();
237 uint8_t _transfer_s(uint8_t bt);
242 static spi_trans spi_trans_array[SPI_LOG_SIZE];
243 static uint8_t spi_trans_ptr;
F4Light::Semaphore * get_semaphore()
struct F4Light::SPIDESC SPIDesc
void register_completion_callback(AP_HAL::Proc proc)
void write(uint8_t value)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
enum F4Light::SPI_TRANSFER_MODE SPI_transferMode
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
void spi_set_speed(const spi_dev *dev, uint16_t baudPrescaler)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb proc) override
static void spi_wait_busy(const spi_dev *dev)
void register_completion_callback(AP_HAL::MemberProc proc)
uint8_t(* spi_WaitFunc)(uint8_t b)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
const uint8_t * _send_address
bool unregister_callback(PeriodicHandle h)
spi_mode
SPI mode configuration.
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us)
static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h)
void init()
Generic board initialization function.
spi_baud_rate
SPI baud rate configuration, as a divisor of f_PCLK, the PCLK clock frequency.
static void delay_ns100(uint32_t us)