181 for (
int i = 0;
i < len ;
i++)
286 uint32_t timeout = 100000;
#define DMA_MemoryInc_Enable
void init_UART(uint32_t baudrate_, uart_mode_t mode=MODE_8N1)
bool tx_buffer_empty() override
void init(const uart_hardware_struct_t *conf, uint32_t baudrate_, uart_mode_t mode=MODE_8N1)
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.
void register_rx_callback(void(*cb)(uint8_t data)) override
DMA Init structure definition.
uint16_t USART_HardwareFlowControl
#define DMA_MemoryDataSize_Byte
void DMA_Tx_IRQ_callback()
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
#define DMA_PeripheralInc_Disable
std::function< void(uint8_t)> receive_CB_
void put_byte(uint8_t ch) override
uint32_t DMA_MemoryDataSize
#define DMA_Priority_High
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 rx_buffer_[RX_BUFFER_SIZE]
uint8_t NVIC_IRQChannelSubPriority
uint32_t DMA_PeripheralInc
#define DMA_DIR_MemoryToPeripheral
NVIC Init Structure definition.
void USART_ITConfig(USART_TypeDef *USARTx, uint16_t USART_IT, FunctionalState NewState)
Enables or disables the specified USART interrupts.
const uart_hardware_struct_t * c_
ITStatus DMA_GetITStatus(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT)
Checks whether the specified DMAy Streamx interrupt has occurred or not.
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
uint8_t read_byte() override
#define USART_HardwareFlowControl_None
#define USART_WordLength_8b
uint32_t tx_bytes_free() override
void DMA1_Stream1_IRQHandler(void)
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
void DMA2_Stream5_IRQHandler(void)
void USART_DMACmd(USART_TypeDef *USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
Enables or disables the USART's DMA interface.
uint32_t DMA_PeripheralBurst
#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
void USART1_IRQHandler(void)
uint32_t DMA_Memory0BaseAddr
uint16_t USART_WordLength
#define DMA_MemoryBurst_Single
uint32_t DMA_FIFOThreshold
FunctionalState NVIC_IRQChannelCmd
void USART_Init(USART_TypeDef *USARTx, USART_InitTypeDef *USART_InitStruct)
Initializes the USARTx peripheral according to the specified parameters in the USART_InitStruct ...
uint8_t tx_buffer_[TX_BUFFER_SIZE]
void DMA1_Stream3_IRQHandler(void)
uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef *DMAy_Streamx)
Returns the number of remaining data units in the current DMAy Streamx transfer.
uint8_t NVIC_IRQChannelPreemptionPriority
void USART_Cmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the specified USART peripheral.
#define DMA_FIFOMode_Disable
FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef *DMAy_Streamx)
Returns the status of EN bit for the specified DMAy Streamx.
void DMA2_Stream7_IRQHandler(void)
#define DMA_PeripheralDataSize_Byte
uint32_t rx_bytes_waiting() override
bool set_mode(uint32_t baud, uart_mode_t mode)
void DMA_Rx_IRQ_callback()
#define DMA_DIR_PeripheralToMemory
#define USART_Parity_Even
void USART3_IRQHandler(void)
#define DMA_Mode_Circular
DMA_Stream_TypeDef * Rx_DMA_Stream
void write(const uint8_t *ch, uint8_t len) override
USART Init Structure definition.
void DMA_SetCurrDataCounter(DMA_Stream_TypeDef *DMAy_Streamx, uint16_t Counter)
Writes the number of data units to be transferred on the DMAy Streamx.
void unregister_rx_callback() override
DMA_Stream_TypeDef * Tx_DMA_Stream
#define DMA_PeripheralBurst_Single