mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
rewritten drv_uart to suck slightly less
tested w/o GPS git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@382 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
1ff0036dec
commit
cbb580f753
10 changed files with 403 additions and 321 deletions
451
src/drv_uart.c
451
src/drv_uart.c
|
@ -1,60 +1,41 @@
|
|||
#include "board.h"
|
||||
|
||||
/*
|
||||
DMA UART routines idea lifted from AutoQuad
|
||||
Copyright © 2011 Bill Nesbitt
|
||||
*/
|
||||
#define UART_BUFFER_SIZE 256
|
||||
|
||||
// Receive buffer, circular DMA
|
||||
volatile uint8_t rxBuffer[UART_BUFFER_SIZE];
|
||||
volatile uint32_t rxDMAPos = 0;
|
||||
volatile uint8_t txBuffer[UART_BUFFER_SIZE];
|
||||
volatile uint32_t txBufferTail = 0;
|
||||
volatile uint32_t txBufferHead = 0;
|
||||
volatile bool txDMAEmpty = false;
|
||||
static serialPort_t serialPort1;
|
||||
static serialPort_t serialPort2;
|
||||
|
||||
static void uartTxDMA(void)
|
||||
{
|
||||
DMA1_Channel4->CMAR = (uint32_t)&txBuffer[txBufferTail];
|
||||
if (txBufferHead > txBufferTail) {
|
||||
DMA1_Channel4->CNDTR = txBufferHead - txBufferTail;
|
||||
txBufferTail = txBufferHead;
|
||||
} else {
|
||||
DMA1_Channel4->CNDTR = UART_BUFFER_SIZE - txBufferTail;
|
||||
txBufferTail = 0;
|
||||
}
|
||||
txDMAEmpty = false;
|
||||
DMA_Cmd(DMA1_Channel4, ENABLE);
|
||||
}
|
||||
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||
DMA_Cmd(DMA1_Channel4, DISABLE);
|
||||
|
||||
if (txBufferHead != txBufferTail)
|
||||
uartTxDMA();
|
||||
else
|
||||
txDMAEmpty = true;
|
||||
}
|
||||
|
||||
void uartInit(uint32_t speed)
|
||||
// USART1 - Telemetry (RX/TX by DMA)
|
||||
serialPort_t *serialUSART1(uint32_t baudRate, portmode_t mode)
|
||||
{
|
||||
serialPort_t *s;
|
||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &serialPort1;
|
||||
s->rxBufferSize = UART1_RX_BUFFER_SIZE;
|
||||
s->txBufferSize = UART1_TX_BUFFER_SIZE;
|
||||
s->rxBuffer = rx1Buffer;
|
||||
s->txBuffer = tx1Buffer;
|
||||
s->rxDMAChannel = DMA1_Channel5;
|
||||
s->txDMAChannel = DMA1_Channel4;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
// USART1_TX PA9
|
||||
// USART1_RX PA10
|
||||
gpio.pin = Pin_9;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.pin = Pin_9;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
if (mode & MODE_TX)
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpio.pin = Pin_10;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
if (mode & MODE_RX)
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
// DMA TX Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn;
|
||||
|
@ -63,191 +44,255 @@ void uartInit(uint32_t speed)
|
|||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
USART_InitStructure.USART_BaudRate = speed;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
|
||||
USART_Init(USART1, &USART_InitStructure);
|
||||
|
||||
// Receive DMA into a circular buffer
|
||||
DMA_DeInit(DMA1_Channel5);
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)rxBuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
DMA_InitStructure.DMA_BufferSize = UART_BUFFER_SIZE;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_Init(DMA1_Channel5, &DMA_InitStructure);
|
||||
|
||||
DMA_Cmd(DMA1_Channel5, ENABLE);
|
||||
USART_DMACmd(USART1, USART_DMAReq_Rx, ENABLE);
|
||||
rxDMAPos = DMA_GetCurrDataCounter(DMA1_Channel5);
|
||||
|
||||
// Transmit DMA
|
||||
DMA_DeInit(DMA1_Channel4);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_Init(DMA1_Channel4, &DMA_InitStructure);
|
||||
DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, ENABLE);
|
||||
DMA1_Channel4->CNDTR = 0;
|
||||
USART_DMACmd(USART1, USART_DMAReq_Tx, ENABLE);
|
||||
|
||||
USART_Cmd(USART1, ENABLE);
|
||||
return s;
|
||||
}
|
||||
|
||||
bool isUartAvailable(void)
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
serialPort_t *serialUSART2(uint32_t baudRate, portmode_t mode)
|
||||
{
|
||||
return (DMA_GetCurrDataCounter(DMA1_Channel5) != rxDMAPos) ? true : false;
|
||||
}
|
||||
|
||||
bool isUartTransmitDMAEmpty(void)
|
||||
{
|
||||
return txDMAEmpty;
|
||||
}
|
||||
|
||||
bool isUartTransmitEmpty(void)
|
||||
{
|
||||
return (txBufferTail == txBufferHead);
|
||||
}
|
||||
|
||||
uint8_t uartRead(void)
|
||||
{
|
||||
uint8_t ch;
|
||||
|
||||
ch = rxBuffer[UART_BUFFER_SIZE - rxDMAPos];
|
||||
// go back around the buffer
|
||||
if (--rxDMAPos == 0)
|
||||
rxDMAPos = UART_BUFFER_SIZE;
|
||||
|
||||
return ch;
|
||||
}
|
||||
|
||||
uint8_t uartReadPoll(void)
|
||||
{
|
||||
while (!isUartAvailable()); // wait for some bytes
|
||||
return uartRead();
|
||||
}
|
||||
|
||||
void uartWrite(uint8_t ch)
|
||||
{
|
||||
txBuffer[txBufferHead] = ch;
|
||||
txBufferHead = (txBufferHead + 1) % UART_BUFFER_SIZE;
|
||||
|
||||
// if DMA wasn't enabled, fire it up
|
||||
if (!(DMA1_Channel4->CCR & 1))
|
||||
uartTxDMA();
|
||||
}
|
||||
|
||||
void uartPrint(char *str)
|
||||
{
|
||||
while (*str)
|
||||
uartWrite(*(str++));
|
||||
}
|
||||
|
||||
/* -------------------------- UART2 (Spektrum, GPS) ----------------------------- */
|
||||
uartReceiveCallbackPtr uart2Callback = NULL;
|
||||
#define UART2_BUFFER_SIZE 128
|
||||
|
||||
volatile uint8_t tx2Buffer[UART2_BUFFER_SIZE];
|
||||
uint32_t tx2BufferTail = 0;
|
||||
uint32_t tx2BufferHead = 0;
|
||||
bool uart2RxOnly = false;
|
||||
|
||||
static void uart2Open(uint32_t speed)
|
||||
{
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
||||
USART_StructInit(&USART_InitStructure);
|
||||
USART_InitStructure.USART_BaudRate = speed;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_Mode = USART_Mode_Rx | (uart2RxOnly ? 0 : USART_Mode_Tx);
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_Init(USART2, &USART_InitStructure);
|
||||
USART_Cmd(USART2, ENABLE);
|
||||
}
|
||||
|
||||
void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly)
|
||||
{
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
serialPort_t *s;
|
||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &serialPort2;
|
||||
s->baudRate = baudRate;
|
||||
s->rxBufferSize = UART2_RX_BUFFER_SIZE;
|
||||
s->txBufferSize = UART2_TX_BUFFER_SIZE;
|
||||
s->rxBuffer = rx2Buffer;
|
||||
s->txBuffer = tx2Buffer;
|
||||
s->USARTx = USART2;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
// USART2_TX PA2
|
||||
// USART2_RX PA3
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.pin = GPIO_Pin_2;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
if (mode & MODE_TX)
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpio.pin = Pin_3;
|
||||
gpio.mode = Mode_IPU;
|
||||
if (mode & MODE_RX)
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
uart2RxOnly = rxOnly;
|
||||
|
||||
// RX/TX Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
// USART2_TX PA2
|
||||
// USART2_RX PA3
|
||||
gpio.pin = GPIO_Pin_2;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
if (!rxOnly)
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpio.pin = Pin_3;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
uart2Open(speed);
|
||||
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
|
||||
if (!rxOnly)
|
||||
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
|
||||
uart2Callback = func;
|
||||
return s;
|
||||
}
|
||||
|
||||
void uart2ChangeBaud(uint32_t speed)
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode)
|
||||
{
|
||||
uart2Open(speed);
|
||||
}
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
serialPort_t *s = NULL;
|
||||
|
||||
void uart2Write(uint8_t ch)
|
||||
{
|
||||
if (uart2RxOnly)
|
||||
return;
|
||||
if (USARTx == USART1)
|
||||
s = serialUSART1(baudRate, mode);
|
||||
if (USARTx == USART2)
|
||||
s = serialUSART2(baudRate, mode);
|
||||
|
||||
tx2Buffer[tx2BufferHead] = ch;
|
||||
tx2BufferHead = (tx2BufferHead + 1) % UART2_BUFFER_SIZE;
|
||||
s->USARTx = USARTx;
|
||||
s->rxBufferHead = s->rxBufferTail = 0;
|
||||
s->txBufferHead = s->txBufferTail = 0;
|
||||
// callback for IRQ-based RX ONLY
|
||||
s->callback = callback;
|
||||
s->mode = mode;
|
||||
|
||||
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
|
||||
}
|
||||
USART_InitStructure.USART_BaudRate = baudRate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_InitStructure.USART_Mode = 0;
|
||||
if (mode & MODE_RX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||
if (mode & MODE_TX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||
USART_Init(USARTx, &USART_InitStructure);
|
||||
USART_Cmd(USARTx, ENABLE);
|
||||
|
||||
bool isUart2TransmitEmpty(void)
|
||||
{
|
||||
return tx2BufferTail == tx2BufferHead;
|
||||
}
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->DR;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uint16_t SR = USART2->SR;
|
||||
|
||||
if (SR & USART_IT_RXNE) {
|
||||
if (uart2Callback)
|
||||
uart2Callback(USART_ReceiveData(USART2));
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (tx2BufferTail != tx2BufferHead) {
|
||||
USART2->DR = tx2Buffer[tx2BufferTail];
|
||||
tx2BufferTail = (tx2BufferTail + 1) % UART2_BUFFER_SIZE;
|
||||
// Receive DMA or IRQ
|
||||
if (mode & MODE_RX) {
|
||||
if (s->rxDMAChannel) {
|
||||
DMA_InitStructure.DMA_BufferSize = s->rxBufferSize;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->rxBuffer;
|
||||
DMA_DeInit(s->rxDMAChannel);
|
||||
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
|
||||
DMA_Cmd(s->rxDMAChannel, ENABLE);
|
||||
USART_DMACmd(USARTx, USART_DMAReq_Rx, ENABLE);
|
||||
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
|
||||
} else {
|
||||
USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
|
||||
USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
// Transmit DMA or IRQ
|
||||
if (mode & MODE_TX) {
|
||||
if (s->txDMAChannel) {
|
||||
DMA_InitStructure.DMA_BufferSize = s->txBufferSize;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_DeInit(s->txDMAChannel);
|
||||
DMA_Init(s->txDMAChannel, &DMA_InitStructure);
|
||||
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
|
||||
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
|
||||
s->txDMAChannel->CNDTR = 0;
|
||||
USART_DMACmd(USARTx, USART_DMAReq_Tx, ENABLE);
|
||||
} else {
|
||||
USART_ITConfig(USARTx, USART_IT_TXE, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
void uartChangeBaud(serialPort_t *s, uint32_t baudRate)
|
||||
{
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baudRate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_InitStructure.USART_Mode = 0;
|
||||
if (s->mode & MODE_RX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||
if (s->mode & MODE_TX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||
USART_Init(s->USARTx, &USART_InitStructure);
|
||||
}
|
||||
|
||||
static void uartStartTxDMA(serialPort_t *s)
|
||||
{
|
||||
s->txDMAChannel->CMAR = (uint32_t)&s->txBuffer[s->txBufferTail];
|
||||
if (s->txBufferHead > s->txBufferTail) {
|
||||
s->txDMAChannel->CNDTR = s->txBufferHead - s->txBufferTail;
|
||||
s->txBufferTail = s->txBufferHead;
|
||||
} else {
|
||||
s->txDMAChannel->CNDTR = s->txBufferSize - s->txBufferTail;
|
||||
s->txBufferTail = 0;
|
||||
}
|
||||
s->txDMAEmpty = false;
|
||||
DMA_Cmd(s->txDMAChannel, ENABLE);
|
||||
}
|
||||
|
||||
bool isUartAvailable(serialPort_t *s)
|
||||
{
|
||||
if (s->rxDMAChannel)
|
||||
return s->rxDMAChannel->CNDTR != s->rxDMAPos;
|
||||
else
|
||||
return s->rxBufferTail != s->rxBufferHead;
|
||||
}
|
||||
|
||||
// BUGBUG TODO TODO FIXME
|
||||
bool isUartTransmitEmpty(serialPort_t *s)
|
||||
{
|
||||
if (s->txDMAChannel)
|
||||
return s->txDMAEmpty;
|
||||
else
|
||||
return s->txBufferTail == s->txBufferHead;
|
||||
}
|
||||
|
||||
uint8_t uartRead(serialPort_t *s)
|
||||
{
|
||||
uint8_t ch;
|
||||
|
||||
if (s->rxDMAChannel) {
|
||||
ch = s->rxBuffer[s->rxBufferSize - s->rxDMAPos];
|
||||
if (--s->rxDMAPos == 0)
|
||||
s->rxDMAPos = s->rxBufferSize;
|
||||
} else {
|
||||
ch = s->rxBuffer[s->rxBufferTail];
|
||||
s->rxBufferTail = (s->rxBufferTail + 1) % s->rxBufferSize;
|
||||
}
|
||||
|
||||
return ch;
|
||||
}
|
||||
|
||||
void uartWrite(serialPort_t *s, uint8_t ch)
|
||||
{
|
||||
s->txBuffer[s->txBufferHead] = ch;
|
||||
s->txBufferHead = (s->txBufferHead + 1) % s->txBufferSize;
|
||||
|
||||
if (s->txDMAChannel) {
|
||||
if (!(s->txDMAChannel->CCR & 1))
|
||||
uartStartTxDMA(s);
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
// Handlers
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort1;
|
||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||
|
||||
if (s->txBufferHead != s->txBufferTail)
|
||||
uartStartTxDMA(s);
|
||||
else
|
||||
s->txDMAEmpty = true;
|
||||
}
|
||||
|
||||
// USART1 Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort1;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->txBufferTail != s->txBufferHead) {
|
||||
s->USARTx->DR = s->txBuffer[s->txBufferTail];
|
||||
s->txBufferTail = (s->txBufferTail + 1) % s->txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// USART2 Rx/Tx IRQ Handler
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort2;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_RXNE) {
|
||||
// If we registered a callback, pass crap there
|
||||
if (s->callback) {
|
||||
s->callback(s->USARTx->DR);
|
||||
} else {
|
||||
s->rxBuffer[s->rxBufferHead] = s->USARTx->DR;
|
||||
s->rxBufferHead = (s->rxBufferHead + 1) % s->rxBufferSize;
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->txBufferTail != s->txBufferHead) {
|
||||
s->USARTx->DR = s->txBuffer[s->txBufferTail];
|
||||
s->txBufferTail = (s->txBufferTail + 1) % s->txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue