113 const uint16_t clearBRP = 0xFFC7;
171 if ((--spiTimeout) == 0)
181 if ((--spiTimeout) == 0)
#define DMA_MemoryInc_Enable
void transfer_complete_cb()
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
#define DMA_MemoryDataSize_Byte
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx/I2Sx peripheral.
void DMA2_Stream3_IRQHandler()
uint16_t SPI_BaudRatePrescaler
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
#define DMA_PeripheralInc_Disable
const spi_hardware_struct_t * c_
bool transfer(uint8_t *out_data, uint32_t num_bytes, uint8_t *in_data, GPIO *cs=NULL, void(*cb)(void)=NULL)
void(* transfer_cb_)(void)
uint16_t SPI_CRCPolynomial
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
Deinitializes the SPIx peripheral registers to their default reset values.
uint32_t DMA_MemoryDataSize
DMA_Stream_TypeDef * Rx_DMA_Stream
static uint8_t dummy_buffer[256]
#define DMA_Priority_High
#define SPI_I2S_DMAReq_Tx
void DMA_Init(DMA_Stream_TypeDef *DMAy_Streamx, DMA_InitTypeDef *DMA_InitStruct)
Initializes the DMAy Streamx according to the specified parameters in the DMA_InitStruct structure...
uint8_t NVIC_IRQChannelSubPriority
#define SPI_BaudRatePrescaler_32
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Checks whether the specified SPI flag is set or not.
uint32_t DMA_PeripheralInc
#define DMA_DIR_MemoryToPeripheral
NVIC Init Structure definition.
bool write(const uint8_t *out_data, uint32_t num_bytes, GPIO *cs=NULL)
ITStatus DMA_GetITStatus(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT)
Checks whether the specified DMAy Streamx interrupt has occurred or not.
#define SPI_BaudRatePrescaler_256
const uint8_t * out_buffer_ptr_
void DMA_ClearITPendingBit(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT)
Clears the DMAy Streamx's interrupt pending bits.
void DMA_ITConfig(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState)
Enables or disables the specified DMAy Streamx interrupts.
uint32_t DMA_PeripheralDataSize
void SPI_CalculateCRC(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the CRC value calculation of the transferred bytes.
#define SPI_BaudRatePrescaler_16
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
uint32_t DMA_PeripheralBurst
void SPI_I2S_DMACmd(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
Enables or disables the SPIx/I2Sx DMA interface.
#define SPI_BaudRatePrescaler_2
static volatile int16_t temp
#define DMA_FIFOThreshold_1QuarterFull
void DMA_Cmd(DMA_Stream_TypeDef *DMAy_Streamx, FunctionalState NewState)
Enables or disables the specified DMAy Streamx.
uint32_t DMA_PeripheralBaseAddr
SPI Init structure definition.
uint32_t DMA_Memory0BaseAddr
#define SPI_Direction_2Lines_FullDuplex
#define DMA_MemoryBurst_Single
#define SPI_I2S_FLAG_RXNE
uint32_t DMA_FIFOThreshold
void DMA1_Stream5_IRQHandler()
void SPI_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral.
FunctionalState NVIC_IRQChannelCmd
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitTypeDef *SPI_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the SPI_InitStruct.
uint8_t transfer_byte(uint8_t data, GPIO *cs=NULL)
#define SPI_BaudRatePrescaler_128
#define SPI_BaudRatePrescaler_64
void write(gpio_write_t state)
uint8_t NVIC_IRQChannelPreemptionPriority
#define DMA_FIFOMode_Disable
void DMA1_Stream4_IRQHandler()
void set_divisor(uint16_t new_divisor)
#define DMA_PeripheralDataSize_Byte
DMA_InitTypeDef DMA_InitStructure_
void init(const spi_hardware_struct_t *conf)
#define DMA_DIR_PeripheralToMemory
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data)
Transmits a Data through the SPIx/I2Sx peripheral.
#define SPI_BaudRatePrescaler_4
void DMA_ClearFlag(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Clears the DMAy Streamx's pending flags.
DMA_Stream_TypeDef * Tx_DMA_Stream
#define SPI_BaudRatePrescaler_8
#define SPI_I2S_DMAReq_Rx
#define DMA_PeripheralBurst_Single