mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
merge branch master into osd-improvement-master
This commit is contained in:
commit
b909c70353
138 changed files with 1104 additions and 1533 deletions
|
@ -31,14 +31,6 @@
|
|||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
// Using RX DMA disables the use of receive callbacks
|
||||
//#define USE_USART1_RX_DMA
|
||||
//#define USE_USART2_RX_DMA
|
||||
//#define USE_USART3_RX_DMA
|
||||
//#define USE_USART4_RX_DMA
|
||||
//#define USE_USART5_RX_DMA
|
||||
//#define USE_USART6_RX_DMA
|
||||
|
||||
#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
|
||||
|
||||
|
@ -72,20 +64,20 @@ typedef struct uartDevice_s {
|
|||
} uartDevice_t;
|
||||
|
||||
//static uartPort_t uartPort[MAX_UARTS];
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
static uartDevice_t uart1 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
.txDMAStream = DMA2_Stream7,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA2_Stream5,
|
||||
#endif
|
||||
.dev = USART1,
|
||||
.rx = IO_TAG(USART1_RX_PIN),
|
||||
.tx = IO_TAG(USART1_TX_PIN),
|
||||
.rx = IO_TAG(UART1_RX_PIN),
|
||||
.tx = IO_TAG(UART1_TX_PIN),
|
||||
.af = GPIO_AF_USART1,
|
||||
#ifdef USART1_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART1_AHB1_PERIPHERALS,
|
||||
#ifdef UART1_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb2 = RCC_APB2(USART1),
|
||||
.txIrq = DMA2_ST7_HANDLER,
|
||||
|
@ -95,20 +87,20 @@ static uartDevice_t uart1 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
static uartDevice_t uart2 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART2_RX_DMA
|
||||
#ifdef USE_UART2_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream5,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream6,
|
||||
.dev = USART2,
|
||||
.rx = IO_TAG(USART2_RX_PIN),
|
||||
.tx = IO_TAG(USART2_TX_PIN),
|
||||
.rx = IO_TAG(UART2_RX_PIN),
|
||||
.tx = IO_TAG(UART2_TX_PIN),
|
||||
.af = GPIO_AF_USART2,
|
||||
#ifdef USART2_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART2_AHB1_PERIPHERALS,
|
||||
#ifdef UART2_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(USART2),
|
||||
.txIrq = DMA1_ST6_HANDLER,
|
||||
|
@ -118,20 +110,20 @@ static uartDevice_t uart2 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
static uartDevice_t uart3 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART3_RX_DMA
|
||||
#ifdef USE_UART3_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream1,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream3,
|
||||
.dev = USART3,
|
||||
.rx = IO_TAG(USART3_RX_PIN),
|
||||
.tx = IO_TAG(USART3_TX_PIN),
|
||||
.rx = IO_TAG(UART3_RX_PIN),
|
||||
.tx = IO_TAG(UART3_TX_PIN),
|
||||
.af = GPIO_AF_USART3,
|
||||
#ifdef USART3_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART3_AHB1_PERIPHERALS,
|
||||
#ifdef UART3_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(USART3),
|
||||
.txIrq = DMA1_ST3_HANDLER,
|
||||
|
@ -141,20 +133,20 @@ static uartDevice_t uart3 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
static uartDevice_t uart4 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream2,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream4,
|
||||
.dev = UART4,
|
||||
.rx = IO_TAG(USART4_RX_PIN),
|
||||
.tx = IO_TAG(USART4_TX_PIN),
|
||||
.rx = IO_TAG(UART4_RX_PIN),
|
||||
.tx = IO_TAG(UART4_TX_PIN),
|
||||
.af = GPIO_AF_UART4,
|
||||
#ifdef USART4_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART4_AHB1_PERIPHERALS,
|
||||
#ifdef UART4_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(UART4),
|
||||
.txIrq = DMA1_ST4_HANDLER,
|
||||
|
@ -164,20 +156,20 @@ static uartDevice_t uart4 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
static uartDevice_t uart5 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream0,
|
||||
#endif
|
||||
.txDMAStream = DMA2_Stream7,
|
||||
.dev = UART5,
|
||||
.rx = IO_TAG(USART5_RX_PIN),
|
||||
.tx = IO_TAG(USART5_TX_PIN),
|
||||
.rx = IO_TAG(UART5_RX_PIN),
|
||||
.tx = IO_TAG(UART5_TX_PIN),
|
||||
.af = GPIO_AF_UART5,
|
||||
#ifdef USART5_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART5_AHB1_PERIPHERALS,
|
||||
#ifdef UART5_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(UART5),
|
||||
.txIrq = DMA2_ST7_HANDLER,
|
||||
|
@ -187,20 +179,20 @@ static uartDevice_t uart5 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
static uartDevice_t uart6 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_5,
|
||||
#ifdef USE_USART6_RX_DMA
|
||||
#ifdef USE_UART6_RX_DMA
|
||||
.rxDMAStream = DMA2_Stream1,
|
||||
#endif
|
||||
.txDMAStream = DMA2_Stream6,
|
||||
.dev = USART6,
|
||||
.rx = IO_TAG(USART6_RX_PIN),
|
||||
.tx = IO_TAG(USART6_TX_PIN),
|
||||
.rx = IO_TAG(UART6_RX_PIN),
|
||||
.tx = IO_TAG(UART6_TX_PIN),
|
||||
.af = GPIO_AF_USART6,
|
||||
#ifdef USART6_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART6_AHB1_PERIPHERALS,
|
||||
#ifdef UART6_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb2 = RCC_APB2(USART6),
|
||||
.txIrq = DMA2_ST6_HANDLER,
|
||||
|
@ -211,39 +203,39 @@ static uartDevice_t uart6 =
|
|||
#endif
|
||||
|
||||
static uartDevice_t* uartHardwareMap[] = {
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
&uart1,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
&uart2,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
&uart3,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
&uart4,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
&uart5,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
&uart6,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
};
|
||||
|
||||
void usartIrqHandler(uartPort_t *s)
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
||||
if (s->port.callback) {
|
||||
|
@ -302,24 +294,24 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
|
|||
}
|
||||
}
|
||||
|
||||
uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
uartDevice_t *uart = uartHardwareMap[device];
|
||||
if (!uart) return NULL;
|
||||
|
||||
|
||||
s = &(uart->port);
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
|
||||
s->port.rxBuffer = uart->rxBuffer;
|
||||
s->port.txBuffer = uart->txBuffer;
|
||||
s->port.rxBufferSize = sizeof(uart->rxBuffer);
|
||||
s->port.txBufferSize = sizeof(uart->txBuffer);
|
||||
|
||||
|
||||
s->USARTx = uart->dev;
|
||||
if (uart->rxDMAStream) {
|
||||
s->rxDMAChannel = uart->DMAChannel;
|
||||
|
@ -327,34 +319,34 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p
|
|||
}
|
||||
s->txDMAChannel = uart->DMAChannel;
|
||||
s->txDMAStream = uart->txDMAStream;
|
||||
|
||||
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
|
||||
IO_t tx = IOGetByTag(uart->tx);
|
||||
IO_t rx = IOGetByTag(uart->rx);
|
||||
|
||||
|
||||
if (uart->rcc_apb2)
|
||||
RCC_ClockCmd(uart->rcc_apb2, ENABLE);
|
||||
|
||||
|
||||
if (uart->rcc_apb1)
|
||||
RCC_ClockCmd(uart->rcc_apb1, ENABLE);
|
||||
|
||||
|
||||
if (uart->rcc_ahb1)
|
||||
RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
|
||||
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
||||
}
|
||||
else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||
}
|
||||
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_USART);
|
||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
||||
}
|
||||
}
|
||||
|
@ -373,86 +365,86 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p
|
|||
return s;
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART1
|
||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_1, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_1, baudRate, mode, options);
|
||||
}
|
||||
|
||||
// USART1 Rx/Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_2, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_2, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
// USART3
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_3, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_3, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART3_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
// USART4
|
||||
uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_4, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_4, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void UART4_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
// USART5
|
||||
uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_5, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_5, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void UART5_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
// USART6
|
||||
uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_6, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_6, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART6_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue