mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 07:15:18 +03:00
CC3D - Support serial RX on UART1.
This commit is contained in:
parent
7b8ad20af6
commit
e81cc9696e
2 changed files with 22 additions and 15 deletions
|
@ -47,13 +47,18 @@ static uartPort_t uartPort2;
|
||||||
static uartPort_t uartPort3;
|
static uartPort_t uartPort3;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Using RX DMA disables the use of receive callbacks
|
||||||
|
#if !defined(CC3D) // FIXME move board specific code to target.h files.
|
||||||
|
#define USE_USART1_RX_DMA
|
||||||
|
#endif
|
||||||
|
|
||||||
void uartStartTxDMA(uartPort_t *s);
|
void uartStartTxDMA(uartPort_t *s);
|
||||||
|
|
||||||
void usartIrqCallback(uartPort_t *s)
|
void usartIrqCallback(uartPort_t *s)
|
||||||
{
|
{
|
||||||
uint16_t SR = s->USARTx->SR;
|
uint16_t SR = s->USARTx->SR;
|
||||||
|
|
||||||
if (SR & USART_FLAG_RXNE) {
|
if (SR & USART_FLAG_RXNE && !s->rxDMAChannel) {
|
||||||
// If we registered a callback, pass crap there
|
// If we registered a callback, pass crap there
|
||||||
if (s->port.callback) {
|
if (s->port.callback) {
|
||||||
s->port.callback(s->USARTx->DR);
|
s->port.callback(s->USARTx->DR);
|
||||||
|
@ -98,11 +103,13 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
||||||
|
|
||||||
s->USARTx = USART1;
|
s->USARTx = USART1;
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
|
|
||||||
|
#ifdef USE_USART1_RX_DMA
|
||||||
s->rxDMAChannel = DMA1_Channel5;
|
s->rxDMAChannel = DMA1_Channel5;
|
||||||
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
#endif
|
||||||
s->txDMAChannel = DMA1_Channel4;
|
s->txDMAChannel = DMA1_Channel4;
|
||||||
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||||
|
@ -129,6 +136,15 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
|
#ifndef USE_USART1_RX_DMA
|
||||||
|
// RX/TX Interrupt
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
#endif
|
||||||
|
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -146,20 +162,11 @@ void DMA1_Channel4_IRQHandler(void)
|
||||||
s->txDMAEmpty = true;
|
s->txDMAEmpty = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// USART1 Tx IRQ Handler
|
// USART1 Rx/Tx IRQ Handler
|
||||||
void USART1_IRQHandler(void)
|
void USART1_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &uartPort1;
|
uartPort_t *s = &uartPort1;
|
||||||
uint16_t SR = s->USARTx->SR;
|
usartIrqCallback(s);
|
||||||
|
|
||||||
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
|
#endif
|
||||||
|
|
|
@ -117,7 +117,7 @@ const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
#ifdef USE_VCP
|
#ifdef USE_VCP
|
||||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||||
#endif
|
#endif
|
||||||
{SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||||
};
|
};
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue