mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
* serial - refactor serial resource handling - port related resources (tx/rx/inverted,dma) - are stored sequentially, with space in place of ports that are not enabled (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT + RESOURCE_SOFTSERIAL_COUNT) - RESOURCE_UART_OFFSET, RESOURCE_LPUART_OFFSET, RESOURCE_SOFTSERIAL_OFFSET - resource entries are pointing into this array (UART, LPUART, SOFTSERIAL) - both pins and DMA - inverter is supproted only for UART + LPUART (makes sense only for UART, to be removed) - softSerialPinConfig is removed, it is no longer necessary - serialResourceIndex(identifier) is used universally to get correct index into resource array - unified handling of resources where possible - serialOwnerTxRx() + serialOwnerIndex() are used for displaying resources correctly to user. - serialType(identifier) implemented - serialOwnerTxRx / serialOwnerIndex are trivial with it - large switch() statemens are greatly simplified * serial - merge code duplicated in all UART implementations - drivers/serial_uart_hw.c contains merged serialUART code. Code did not match exactly. Obvious cases are fixed, more complicated use #ifs - pin inversion unified - uartOpen is refactored a bit * serial - refactor uartDevice - use 'compressed' enum from uartDeviceIdx_e. Only enabled ports are in this enum. - uartDeviceIdx directly indexes uartDevice (no search necessary, no wasted space) - use `serialPortIdentifier_e identifier;` for uartHardware - for DMA remap, define only entries for enabled ports (uartDeviceIdx_e does not exist disabled port) * serial - apply changes to inverter New implementation is trivial * serial - HAL - rxIrq, txIrq replaces by irqn There is only one IRQ for serial * serial - serial_post.h Generated code to normalize target configuration. jinja2 template is used to generate header file. Port handling is unified a lot. SERIAL_<type><n>_USED 0/1 - always defined, value depends on target configuration SERIAL_<type>_MASK - bitmask of used ports or given type. <port>1 is BIT(0) SERIAL_<type>_COUNT - number of enabled ports of given type SERIAL_<type>_MAX - <index of highest used port> + 1, 0 when no port is enabled * targets - remove automatically calculated valued from configs serial_post.h generated it * serial - remove definitions replaced by serial_post.h * serial - change LPUART to UART_LP1 in places LPUART is mostly handled as another UART port, this change reflects it * serial - use ARRAYLEN / ARRAYEND in some places replaces constant that may not match actual array size * serial - adapt softserial to changes * serial - whitespace, comments * softserial - fix serialTimerConfigureTimebase * serial - suspicious code * serial - unittests * serial - cleanup * serial - simpler port names Is this useful ? * serial - no port count for SITL necessary * serial - fix unittests include serial_post.h, some ports are defined, so normalization will work fine * timers - remove obsolete defines from SITL and unittests * serial - cosmetic improvements comments, whitespace, minor refactoring * serial - fix serialInit bug serialPortToDisable was preventing further tests * serial - fix possible NULL pointer dereference * serial - move serialResourceIndex to drivers * serial - refactor pp/od and pulldown/pullup/nopull Centralize serial options handling, decouple it from MCU type Move some code into new drivers/serial_impl.c * serial - make port.identifier valid early in port initialization * serial - fix unittest Code is moved around a bit to make unittests implementation easier * serial - bug - fix off-by-one error uart1/softserial1/lpuart was not working properly because of this * serial - whipespace + formating + style + comments No functional changes * utils - add popcount functions Wrap __builtin_popcount for easier use. Refactor existing code using it. Update code using BITCOUNT macro in dynamic context (BITCOUNT is for compile-time use only) * serial - inverter - simplify code * pinio - prevent array access overflow * serial - refactor SERIAL_BIDIR_* SERIAL_BIDIR_OD / SERIAL_BIDIR_PP SERIAL_PULL_DEFAULT / SERIAL_PULL_NONE / SERIAL_PULL_PD * serial - simplify code minor refactoring - cleaner AVOID_UARTx_FOR_PWM_PPM (unused anyway) - serialFindPortConfiguration* - remove code duplication - use serialType in smartaudio * serial - add port names - const string is assiociated with each compiled-in port (easy to pass around) - findSerialPortByName * cli - improve serialpassthrough - support port options (in current mode argument) - support port names (`serialpassthrough uart1`) - improve error handling; check more parse errors * cli - resources - minor refactor - prevent SERIAL_TX_NONSENSE when parsing resource type - fix possible NULL pointer dereference - store resource tag only after checking all conditions - slighty better error reporting - `resource serial_tx 1` will print resource assignment * serial - remane pulldown to SERIAL_PULL_SMARTAUDIO Make sure nobody uses it by mistake. SERIAL_PULL_SMARTAUDIO_SUPER_DANGEROUS_USE_AT_YOUR_OWN_RISK_THIS_WILL_BREAK_EVERYTHING_AND_KILL_YOUR_PET_FISH would be better choice, but try shorter version first. * smartaudio - minor refactor/improvement - Fix softserial on AT32 - make it easier to handle SA on per-cpu basis * softserial - minor refactoring no functional changes * UART - move AF handling before MCU dependent code * UART - adapt APM32 / APM32F4 code - Modeled after F4 where possible - come code moved from APM32 to APM32F4, possbily not necessary, but it improves similarity with STM32F4 * UART - APM32 - remove per-pin AF * UART - APM32 - bugfix - fix pinswap #if conditions * UART - apply some improvemnts from APM32 to STM32 * UART - add todo for F4 serial speed * UART - fix typo * UART - refactor support for USE_SMARTAUDIO_NOPULLDOWN * UART - typos, comments, minor improvements * UART - move code into enableRxIrq TODO: split into mcu-specific filer (but in sepatate PR) * UART - add UART_TRAIT_xx makes #if test easier and more consistent more traits shall follow * UART - fix variable name unused branch, would trigger compilation error otherwise * UART - use tables instead of switch * UART - smartaudio minor style change + better comments * UART - unify mspPorts iteration * UART - fix spelling * UART - another typo * UART - fix serialResourceIndex offset must be added, not subtracted offset can be negative * UART - fix typo Bad day ... * UART - use const table GCC does optimize it better. Should not cause functional change * UART - use OwnerIndex for inverter - 1 based - only UART has inversion * UART - refactor serial_resource a bit Single table + helper function. New table is easier to read * UART - serial_impl header is necessary * UART - style-only changes typos unify whitespace comment improvement add some const modifiers use cfg in uartConfigureDma minor improvemnt of for loops * UART - remove LPUART inverter LPUART always supports internal inversion, code was incomplete and unused * UART - update jinja template, regenerate files * UART - enable UART module RCC clk before configuring DMA Does not change anything, UART RCCs are enabled unconditionally
330 lines
10 KiB
C
330 lines
10 KiB
C
/*
|
|
* This file is part of Cleanflight and Betaflight.
|
|
*
|
|
* Cleanflight and Betaflight are free software. You can redistribute
|
|
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
|
|
* 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 this software.
|
|
*
|
|
* If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
/*
|
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
|
*/
|
|
|
|
#include <stdbool.h>
|
|
#include <stdint.h>
|
|
|
|
#include "platform.h"
|
|
|
|
#ifdef USE_UART
|
|
|
|
#include "build/debug.h"
|
|
|
|
#include "drivers/system.h"
|
|
#include "drivers/io.h"
|
|
#include "drivers/dma.h"
|
|
#include "drivers/nvic.h"
|
|
#include "drivers/rcc.h"
|
|
|
|
#include "drivers/serial.h"
|
|
#include "drivers/serial_uart.h"
|
|
#include "drivers/serial_uart_impl.h"
|
|
|
|
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
|
#ifdef USE_UART1
|
|
{
|
|
.identifier = SERIAL_PORT_USART1,
|
|
.reg = USART1,
|
|
.rxDMAChannel = DMA_CHANNEL_4,
|
|
.txDMAChannel = DMA_CHANNEL_4,
|
|
#ifdef USE_UART1_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA2_Stream5,
|
|
#endif
|
|
#ifdef USE_UART1_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA2_Stream7,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
|
|
},
|
|
.txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
|
|
},
|
|
.af = GPIO_AF7_USART1,
|
|
.rcc = RCC_APB2(USART1),
|
|
.irqn = USART1_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART1,
|
|
.txBuffer = uart1TxBuffer,
|
|
.rxBuffer = uart1RxBuffer,
|
|
.txBufferSize = sizeof(uart1TxBuffer),
|
|
.rxBufferSize = sizeof(uart1RxBuffer),
|
|
},
|
|
#endif
|
|
|
|
#ifdef USE_UART2
|
|
{
|
|
.identifier = SERIAL_PORT_USART2,
|
|
.reg = USART2,
|
|
.rxDMAChannel = DMA_CHANNEL_4,
|
|
.txDMAChannel = DMA_CHANNEL_4,
|
|
#ifdef USE_UART2_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA1_Stream5,
|
|
#endif
|
|
#ifdef USE_UART2_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA1_Stream6,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PD6) } },
|
|
.txPins = { { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PD5) } },
|
|
.af = GPIO_AF7_USART2,
|
|
.rcc = RCC_APB1(USART2),
|
|
.irqn = USART2_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART2,
|
|
.txBuffer = uart2TxBuffer,
|
|
.rxBuffer = uart2RxBuffer,
|
|
.txBufferSize = sizeof(uart2TxBuffer),
|
|
.rxBufferSize = sizeof(uart2RxBuffer),
|
|
},
|
|
#endif
|
|
|
|
#ifdef USE_UART3
|
|
{
|
|
.identifier = SERIAL_PORT_USART3,
|
|
.reg = USART3,
|
|
.rxDMAChannel = DMA_CHANNEL_4,
|
|
.txDMAChannel = DMA_CHANNEL_4,
|
|
#ifdef USE_UART3_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA1_Stream1,
|
|
#endif
|
|
#ifdef USE_UART3_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA1_Stream3,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
|
|
.txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
|
|
.af = GPIO_AF7_USART3,
|
|
.rcc = RCC_APB1(USART3),
|
|
.irqn = USART3_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART3,
|
|
.txBuffer = uart3TxBuffer,
|
|
.rxBuffer = uart3RxBuffer,
|
|
.txBufferSize = sizeof(uart3TxBuffer),
|
|
.rxBufferSize = sizeof(uart3RxBuffer),
|
|
},
|
|
#endif
|
|
|
|
#ifdef USE_UART4
|
|
{
|
|
.identifier = SERIAL_PORT_UART4,
|
|
.reg = UART4,
|
|
.rxDMAChannel = DMA_CHANNEL_4,
|
|
.txDMAChannel = DMA_CHANNEL_4,
|
|
#ifdef USE_UART4_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA1_Stream2,
|
|
#endif
|
|
#ifdef USE_UART4_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA1_Stream4,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PA1) }, { DEFIO_TAG_E(PC11) } },
|
|
.txPins = { { DEFIO_TAG_E(PA0) }, { DEFIO_TAG_E(PC10) } },
|
|
.af = GPIO_AF8_UART4,
|
|
.rcc = RCC_APB1(UART4),
|
|
.irqn = UART4_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART4,
|
|
.txBuffer = uart4TxBuffer,
|
|
.rxBuffer = uart4RxBuffer,
|
|
.txBufferSize = sizeof(uart4TxBuffer),
|
|
.rxBufferSize = sizeof(uart4RxBuffer),
|
|
},
|
|
#endif
|
|
|
|
#ifdef USE_UART5
|
|
{
|
|
.identifier = SERIAL_PORT_UART5,
|
|
.reg = UART5,
|
|
.rxDMAChannel = DMA_CHANNEL_4,
|
|
.txDMAChannel = DMA_CHANNEL_4,
|
|
#ifdef USE_UART5_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA1_Stream0,
|
|
#endif
|
|
#ifdef USE_UART5_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA1_Stream7,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PD2) } },
|
|
.txPins = { { DEFIO_TAG_E(PC12) } },
|
|
.af = GPIO_AF8_UART5,
|
|
.rcc = RCC_APB1(UART5),
|
|
.irqn = UART5_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART5,
|
|
.txBuffer = uart5TxBuffer,
|
|
.rxBuffer = uart5RxBuffer,
|
|
.txBufferSize = sizeof(uart5TxBuffer),
|
|
.rxBufferSize = sizeof(uart5RxBuffer),
|
|
},
|
|
#endif
|
|
|
|
#ifdef USE_UART6
|
|
{
|
|
.identifier = SERIAL_PORT_USART6,
|
|
.reg = USART6,
|
|
.rxDMAChannel = DMA_CHANNEL_5,
|
|
.txDMAChannel = DMA_CHANNEL_5,
|
|
#ifdef USE_UART6_RX_DMA
|
|
.rxDMAResource = (dmaResource_t *)DMA2_Stream1,
|
|
#endif
|
|
#ifdef USE_UART6_TX_DMA
|
|
.txDMAResource = (dmaResource_t *)DMA2_Stream6,
|
|
#endif
|
|
.rxPins = { { DEFIO_TAG_E(PC7) }, { DEFIO_TAG_E(PG9) } },
|
|
.txPins = { { DEFIO_TAG_E(PC6) }, { DEFIO_TAG_E(PG14) } },
|
|
.af = GPIO_AF8_USART6,
|
|
.rcc = RCC_APB2(USART6),
|
|
.irqn = USART6_IRQn,
|
|
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
|
|
.rxPriority = NVIC_PRIO_SERIALUART6,
|
|
.txBuffer = uart6TxBuffer,
|
|
.rxBuffer = uart6RxBuffer,
|
|
.txBufferSize = sizeof(uart6TxBuffer),
|
|
.rxBufferSize = sizeof(uart6RxBuffer),
|
|
},
|
|
#endif
|
|
};
|
|
|
|
bool checkUsartTxOutput(uartPort_t *s)
|
|
{
|
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
|
IO_t txIO = IOGetByTag(uart->tx.pin);
|
|
|
|
if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
|
|
if (IORead(txIO)) {
|
|
// TX is high so we're good to transmit
|
|
|
|
// Enable USART TX output
|
|
uart->txPinState = TX_PIN_ACTIVE;
|
|
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->hardware->af);
|
|
|
|
// Enable the UART transmitter
|
|
SET_BIT(s->Handle.Instance->CTRL1, USART_CTRL1_TXEN);
|
|
|
|
return true;
|
|
} else {
|
|
// TX line is pulled low so don't enable USART TX
|
|
return false;
|
|
}
|
|
}
|
|
|
|
return true;
|
|
}
|
|
|
|
void uartTxMonitor(uartPort_t *s)
|
|
{
|
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
|
|
|
if (uart->txPinState == TX_PIN_ACTIVE) {
|
|
IO_t txIO = IOGetByTag(uart->tx.pin);
|
|
|
|
// Disable the UART transmitter
|
|
CLEAR_BIT(s->Handle.Instance->CTRL1, USART_CTRL1_TXEN);
|
|
|
|
// Switch TX to an input with pullup so it's state can be monitored
|
|
uart->txPinState = TX_PIN_MONITOR;
|
|
IOConfigGPIO(txIO, IOCFG_IPU);
|
|
}
|
|
}
|
|
|
|
static void handleUsartTxDma(uartPort_t *s)
|
|
{
|
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
|
|
|
uartTryStartTxDMA(s);
|
|
|
|
if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) {
|
|
// Switch TX to an input with pullup so it's state can be monitored
|
|
uartTxMonitor(s);
|
|
}
|
|
}
|
|
|
|
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
|
|
{
|
|
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
|
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
|
|
{
|
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
|
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
|
|
{
|
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
|
|
}
|
|
handleUsartTxDma(s);
|
|
}
|
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
|
|
{
|
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
|
|
}
|
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
|
|
{
|
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
|
|
}
|
|
}
|
|
|
|
FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
|
|
{
|
|
UART_HandleTypeDef *huart = &s->Handle;
|
|
uint32_t isrflags = READ_REG(huart->Instance->STS);
|
|
uint32_t cr1its = READ_REG(huart->Instance->CTRL1);
|
|
uint32_t cr3its = READ_REG(huart->Instance->CTRL3);
|
|
/* UART in mode Receiver ---------------------------------------------------*/
|
|
if (!s->rxDMAResource && (((isrflags & USART_STS_RXBNEFLG) != RESET) && ((cr1its & USART_CTRL1_RXBNEIEN) != RESET))) {
|
|
if (s->port.rxCallback) {
|
|
s->port.rxCallback(huart->Instance->DATA, s->port.rxCallbackData);
|
|
} else {
|
|
s->port.rxBuffer[s->port.rxBufferHead] = huart->Instance->DATA;
|
|
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
|
}
|
|
}
|
|
|
|
// Detect completion of transmission
|
|
if (((isrflags & USART_STS_TXCFLG) != RESET) && ((cr1its & USART_CTRL1_TXCIEN) != RESET)) {
|
|
// Switch TX to an input with pullup so it's state can be monitored
|
|
uartTxMonitor(s);
|
|
|
|
__DAL_UART_CLEAR_FLAG(huart, UART_IT_TC);
|
|
}
|
|
|
|
if (!s->txDMAResource && (((isrflags & USART_STS_TXBEFLG) != RESET) && ((cr1its & USART_CTRL1_TXBEIEN) != RESET))) {
|
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
|
huart->Instance->DATA = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
|
|
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
|
} else {
|
|
__DAL_UART_DISABLE_IT(huart, UART_IT_TXE);
|
|
}
|
|
}
|
|
|
|
if (((isrflags & USART_STS_OVREFLG) != RESET) && (((cr1its & USART_CTRL1_RXBNEIEN) != RESET)
|
|
|| ((cr3its & USART_CTRL3_ERRIEN) != RESET))) {
|
|
__DAL_UART_CLEAR_OREFLAG(huart);
|
|
}
|
|
|
|
if (((isrflags & USART_STS_IDLEFLG) != RESET) && ((cr1its & USART_STS_IDLEFLG) != RESET)) {
|
|
if (s->port.idleCallback) {
|
|
s->port.idleCallback();
|
|
}
|
|
|
|
// clear
|
|
(void) huart->Instance->STS;
|
|
(void) huart->Instance->DATA;
|
|
}
|
|
}
|
|
|
|
#endif // USE_UART
|