mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 08:45:36 +03:00
CC3D - Support USART3 instead of USART2.
This has highlighted that the existing codebase is quite targeted towards systems that use USART1 and 2. Annoyingly the inverter is on USART1 and the sbus code requires callbacks so still won't work yet.
This commit is contained in:
parent
9906294cd8
commit
b01724681a
9 changed files with 193 additions and 50 deletions
|
@ -34,11 +34,44 @@
|
|||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
|
||||
#ifdef USE_USART1
|
||||
static uartPort_t uartPort1;
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
static uartPort_t uartPort2;
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
static uartPort_t uartPort3;
|
||||
#endif
|
||||
|
||||
void uartStartTxDMA(uartPort_t *s);
|
||||
|
||||
void usartIrqCallback(uartPort_t *s)
|
||||
{
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_RXNE) {
|
||||
// If we registered a callback, pass crap there
|
||||
if (s->port.callback) {
|
||||
s->port.callback(s->USARTx->DR);
|
||||
} else {
|
||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
// USART1 - Telemetry (RX/TX by DMA)
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
|
@ -91,6 +124,39 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
|||
return s;
|
||||
}
|
||||
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||
|
||||
if (s->port.txBufferHead != s->port.txBufferTail)
|
||||
uartStartTxDMA(s);
|
||||
else
|
||||
s->txDMAEmpty = true;
|
||||
}
|
||||
|
||||
// USART1 Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
|
@ -140,58 +206,72 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
|
|||
return s;
|
||||
}
|
||||
|
||||
// Handlers
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||
|
||||
if (s->port.txBufferHead != s->port.txBufferTail)
|
||||
uartStartTxDMA(s);
|
||||
else
|
||||
s->txDMAEmpty = true;
|
||||
}
|
||||
|
||||
// USART1 Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// USART2 Rx/Tx IRQ Handler
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort2;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_RXNE) {
|
||||
// If we registered a callback, pass crap there
|
||||
if (s->port.callback) {
|
||||
s->port.callback(s->USARTx->DR);
|
||||
} else {
|
||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
usartIrqCallback(s);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
// USART3
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort3;
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
s->port.rxBuffer = rx3Buffer;
|
||||
s->port.txBuffer = tx3Buffer;
|
||||
s->port.rxBufferSize = UART3_RX_BUFFER_SIZE;
|
||||
s->port.txBufferSize = UART3_TX_BUFFER_SIZE;
|
||||
|
||||
s->USARTx = USART3;
|
||||
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
#ifdef USART3_APB1_PERIPHERALS
|
||||
RCC_APB1PeriphClockCmd(USART3_APB1_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
#ifdef USART3_APB2_PERIPHERALS
|
||||
RCC_APB2PeriphClockCmd(USART3_APB2_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.pin = USART3_TX_PIN;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
if (mode & MODE_TX)
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
gpio.pin = USART3_RX_PIN;
|
||||
gpio.mode = Mode_IPU;
|
||||
if (mode & MODE_RX)
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
|
||||
// RX/TX Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
// USART2 Rx/Tx IRQ Handler
|
||||
void USART3_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort3;
|
||||
usartIrqCallback(s);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue