1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 23:35:34 +03:00
betaflight/src/main/drivers/serial_uart.c
2017-01-14 00:27:02 +13:00

446 lines
15 KiB
C

/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Authors:
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
* Hamasaki/Timecop - Initial baseflight code
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "build/build_config.h"
#include "common/utils.h"
#include "gpio.h"
#include "inverter.h"
#include "serial.h"
#include "serial_uart.h"
#include "serial_uart_impl.h"
static void usartConfigurePinInversion(uartPort_t *uartPort) {
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
UNUSED(uartPort);
#else
bool inverted = uartPort->port.options & SERIAL_INVERTED;
#ifdef USE_INVERTER
if (inverted) {
// Enable hardware inverter if available.
enableInverter(uartPort->USARTx, true);
}
#endif
#ifdef STM32F303xC
uint32_t inversionPins = 0;
if (uartPort->port.mode & MODE_TX) {
inversionPins |= USART_InvPin_Tx;
}
if (uartPort->port.mode & MODE_RX) {
inversionPins |= USART_InvPin_Rx;
}
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
#endif
#endif
}
static void uartReconfigure(uartPort_t *uartPort)
{
USART_InitTypeDef USART_InitStructure;
USART_Cmd(uartPort->USARTx, DISABLE);
USART_InitStructure.USART_BaudRate = uartPort->port.baudRate;
// according to the stm32 documentation wordlen has to be 9 for parity bits
// this does not seem to matter for rx but will give bad data on tx!
if (uartPort->port.options & SERIAL_PARITY_EVEN) {
USART_InitStructure.USART_WordLength = USART_WordLength_9b;
} else {
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
}
USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = 0;
if (uartPort->port.mode & MODE_RX)
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
if (uartPort->port.mode & MODE_TX)
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
USART_Init(uartPort->USARTx, &USART_InitStructure);
usartConfigurePinInversion(uartPort);
if(uartPort->port.options & SERIAL_BIDIR)
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
else
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
USART_Cmd(uartPort->USARTx, ENABLE);
}
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
uartPort_t *s = NULL;
if (false) {
#ifdef USE_UART1
} else if (USARTx == USART1) {
s = serialUART1(baudRate, mode, options);
#endif
#ifdef USE_UART2
} else if (USARTx == USART2) {
s = serialUART2(baudRate, mode, options);
#endif
#ifdef USE_UART3
} else if (USARTx == USART3) {
s = serialUART3(baudRate, mode, options);
#endif
#ifdef USE_UART4
} else if (USARTx == UART4) {
s = serialUART4(baudRate, mode, options);
#endif
#ifdef USE_UART5
} else if (USARTx == UART5) {
s = serialUART5(baudRate, mode, options);
#endif
#ifdef USE_UART6
} else if (USARTx == USART6) {
s = serialUART6(baudRate, mode, options);
#endif
} else {
return (serialPort_t *)s;
}
s->txDMAEmpty = true;
// common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0;
s->port.txBufferHead = s->port.txBufferTail = 0;
// callback works for IRQ-based RX ONLY
s->port.rxCallback = rxCallback;
s->port.mode = mode;
s->port.baudRate = baudRate;
s->port.options = options;
uartReconfigure(s);
// Receive DMA or IRQ
DMA_InitTypeDef DMA_InitStructure;
if (mode & MODE_RX) {
#ifdef STM32F4
if (s->rxDMAStream) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
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_FIFOMode = DMA_FIFOMode_Disable ;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
#else
if (s->rxDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
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;
#endif
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
#ifdef STM32F4
DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer;
DMA_DeInit(s->rxDMAStream);
DMA_Init(s->rxDMAStream, &DMA_InitStructure);
DMA_Cmd(s->rxDMAStream, ENABLE);
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
#else
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
DMA_DeInit(s->rxDMAChannel);
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
DMA_Cmd(s->rxDMAChannel, ENABLE);
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
#endif
} else {
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
}
}
// Transmit DMA or IRQ
if (mode & MODE_TX) {
#ifdef STM32F4
if (s->txDMAStream) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
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_FIFOMode = DMA_FIFOMode_Disable ;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
#else
if (s->txDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
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;
#endif
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
#ifdef STM32F4
DMA_InitStructure.DMA_Channel = s->txDMAChannel;
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(s->txDMAStream);
DMA_Init(s->txDMAStream, &DMA_InitStructure);
DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
DMA_SetCurrDataCounter(s->txDMAStream, 0);
#else
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;
#endif
USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
}
}
USART_Cmd(s->USARTx, ENABLE);
return (serialPort_t *)s;
}
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
uartPort_t *uartPort = (uartPort_t *)instance;
uartPort->port.baudRate = baudRate;
uartReconfigure(uartPort);
}
void uartSetMode(serialPort_t *instance, portMode_t mode)
{
uartPort_t *uartPort = (uartPort_t *)instance;
uartPort->port.mode = mode;
uartReconfigure(uartPort);
}
void uartStartTxDMA(uartPort_t *s)
{
#ifdef STM32F4
DMA_Cmd(s->txDMAStream, DISABLE);
DMA_MemoryTargetConfig(s->txDMAStream, (uint32_t)&s->port.txBuffer[s->port.txBufferTail], DMA_Memory_0);
//s->txDMAStream->M0AR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
if (s->port.txBufferHead > s->port.txBufferTail) {
s->txDMAStream->NDTR = s->port.txBufferHead - s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead;
}
else {
s->txDMAStream->NDTR = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
DMA_Cmd(s->txDMAStream, ENABLE);
#else
s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
if (s->port.txBufferHead > s->port.txBufferTail) {
s->txDMAChannel->CNDTR = s->port.txBufferHead - s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead;
} else {
s->txDMAChannel->CNDTR = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
DMA_Cmd(s->txDMAChannel, ENABLE);
#endif
}
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
{
const uartPort_t *s = (const uartPort_t*)instance;
#ifdef STM32F4
if (s->rxDMAStream) {
uint32_t rxDMAHead = s->rxDMAStream->NDTR;
#else
if (s->rxDMAChannel) {
uint32_t rxDMAHead = s->rxDMAChannel->CNDTR;
#endif
if (rxDMAHead >= s->rxDMAPos) {
return rxDMAHead - s->rxDMAPos;
} else {
return s->port.rxBufferSize + rxDMAHead - s->rxDMAPos;
}
}
if (s->port.rxBufferHead >= s->port.rxBufferTail) {
return s->port.rxBufferHead - s->port.rxBufferTail;
} else {
return s->port.rxBufferSize + s->port.rxBufferHead - s->port.rxBufferTail;
}
}
uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
{
const uartPort_t *s = (const uartPort_t*)instance;
uint32_t bytesUsed;
if (s->port.txBufferHead >= s->port.txBufferTail) {
bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
} else {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
}
#ifdef STM32F4
if (s->txDMAStream) {
/*
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
* the remaining size of that in-progress transfer here instead:
*/
bytesUsed += s->txDMAStream->NDTR;
#else
if (s->txDMAChannel) {
/*
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
* the remaining size of that in-progress transfer here instead:
*/
bytesUsed += s->txDMAChannel->CNDTR;
#endif
/*
* If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
* space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
* than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
* transmitting a garbage mixture of old and new bytes).
*
* Be kind to callers and pretend like our buffer can only ever be 100% full.
*/
if (bytesUsed >= s->port.txBufferSize - 1) {
return 0;
}
}
return (s->port.txBufferSize - 1) - bytesUsed;
}
bool isUartTransmitBufferEmpty(const serialPort_t *instance)
{
const uartPort_t *s = (const uartPort_t *)instance;
#ifdef STM32F4
if (s->txDMAStream)
#else
if (s->txDMAChannel)
#endif
return s->txDMAEmpty;
else
return s->port.txBufferTail == s->port.txBufferHead;
}
uint8_t uartRead(serialPort_t *instance)
{
uint8_t ch;
uartPort_t *s = (uartPort_t *)instance;
#ifdef STM32F4
if (s->rxDMAStream) {
#else
if (s->rxDMAChannel) {
#endif
ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos];
if (--s->rxDMAPos == 0)
s->rxDMAPos = s->port.rxBufferSize;
} else {
ch = s->port.rxBuffer[s->port.rxBufferTail];
if (s->port.rxBufferTail + 1 >= s->port.rxBufferSize) {
s->port.rxBufferTail = 0;
} else {
s->port.rxBufferTail++;
}
}
return ch;
}
void uartWrite(serialPort_t *instance, uint8_t ch)
{
uartPort_t *s = (uartPort_t *)instance;
s->port.txBuffer[s->port.txBufferHead] = ch;
if (s->port.txBufferHead + 1 >= s->port.txBufferSize) {
s->port.txBufferHead = 0;
} else {
s->port.txBufferHead++;
}
#ifdef STM32F4
if (s->txDMAStream) {
if (!(s->txDMAStream->CR & 1))
#else
if (s->txDMAChannel) {
if (!(s->txDMAChannel->CCR & 1))
#endif
uartStartTxDMA(s);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
}
}
const struct serialPortVTable uartVTable[] = {
{
.serialWrite = uartWrite,
.serialTotalRxWaiting = uartTotalRxBytesWaiting,
.serialTotalTxFree = uartTotalTxBytesFree,
.serialRead = uartRead,
.serialSetBaudRate = uartSetBaudRate,
.isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
.setMode = uartSetMode,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,
}
};