131 if (mode & MODE_RX) {
148 if (mode & MODE_TX) {
const struct serialPortVTable uartVTable[]
#define DMA_MemoryInc_Enable
volatile uint8_t * txBuffer
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
#define DMA_Priority_Medium
uartPort_t * serialUSART1(uint32_t baudRate, portMode_t mode)
volatile uint8_t * rxBuffer
DMA Init structure definition.
uint16_t USART_HardwareFlowControl
const struct serialPortVTable * vTable
Universal Synchronous Asynchronous Receiver Transmitter.
#define RCC_APB2Periph_USART1
#define DMA_MemoryDataSize_Byte
static uartPort_t uartPort1
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
#define DMA_PeripheralInc_Disable
uint32_t DMA_MemoryDataSize
void USART1_IRQHandler(void)
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...
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
static void uartStartTxDMA(uartPort_t *s)
#define UART1_TX_BUFFER_SIZE
uint8_t NVIC_IRQChannelSubPriority
uint32_t DMA_PeripheralInc
NVIC Init Structure definition.
void USART_ITConfig(USART_TypeDef *USARTx, uint16_t USART_IT, FunctionalState NewState)
Enables or disables the specified USART interrupts.
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
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
#define USART_HardwareFlowControl_None
#define USART_WordLength_8b
uint32_t DMA_MemoryBaseAddr
void USART_DMACmd(USART_TypeDef *USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
Enables or disables the USART's DMA interface.
void DMA_StructInit(DMA_InitTypeDef *DMA_InitStruct)
Fills each DMA_InitStruct member with its default value.
void(* serialReceiveCallbackPtr)(uint16_t data)
void DMA_Cmd(DMA_Stream_TypeDef *DMAy_Streamx, FunctionalState NewState)
Enables or disables the specified DMAy Streamx.
uint32_t DMA_PeripheralBaseAddr
DMA_Channel_TypeDef * rxDMAChannel
uint16_t USART_WordLength
#define DMA_DIR_PeripheralSRC
uint8_t uartRead(serialPort_t *instance)
void DMA1_Channel4_IRQHandler(void)
bool isUartTransmitBufferEmpty(serialPort_t *instance)
void uartSetMode(serialPort_t *s, portMode_t mode)
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 ...
#define DMA_DIR_PeripheralDST
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.
serialPort_t * uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode)
void uartWrite(serialPort_t *instance, uint8_t ch)
serialReceiveCallbackPtr callback
#define DMA_PeripheralDataSize_Byte
#define UART1_RX_BUFFER_SIZE
#define USART_Parity_Even
#define DMA_Mode_Circular
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
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.
DMA_Channel_TypeDef * txDMAChannel