1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Refactor uart (#13585)

* 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
This commit is contained in:
Petr Ledvina 2024-11-04 22:07:25 +01:00 committed by GitHub
parent a659189bf0
commit 246d04dc57
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
90 changed files with 2471 additions and 1931 deletions

View file

@ -24,46 +24,26 @@
* 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 <stdlib.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_UART
#include "build/build_config.h"
#include "build/atomic.h"
#include "common/utils.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/inverter.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"
static void usartConfigurePinInversion(uartPort_t *uartPort)
{
#if !defined(USE_INVERTER)
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
#endif
}
// XXX uartReconfigure does not handle resource management properly.
void uartReconfigure(uartPort_t *uartPort)
@ -84,29 +64,25 @@ void uartReconfigure(uartPort_t *uartPort)
if (uartPort->port.mode & MODE_TX)
uartPort->Handle.Init.Mode |= UART_MODE_TX;
usartConfigurePinInversion(uartPort);
// config external pin inverter (no internal pin inversion available)
uartConfigureExternalPinInversion(uartPort);
#ifdef TARGET_USART_CONFIG
// TODO: move declaration into header file
void usartTargetConfigure(uartPort_t *);
usartTargetConfigure(uartPort);
#endif
if (uartPort->port.options & SERIAL_BIDIR)
{
if (uartPort->port.options & SERIAL_BIDIR) {
DAL_HalfDuplex_Init(&uartPort->Handle);
}
else
{
} else {
DAL_UART_Init(&uartPort->Handle);
}
// Receive DMA or IRQ
if (uartPort->port.mode & MODE_RX)
{
if (uartPort->port.mode & MODE_RX) {
#ifdef USE_DMA
if (uartPort->rxDMAResource)
{
if (uartPort->rxDMAResource) {
uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel;
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
@ -170,8 +146,7 @@ void uartReconfigure(uartPort_t *uartPort)
DAL_DMA_DeInit(&uartPort->txDMAHandle);
DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle);
if (status != DAL_OK)
{
if (status != DAL_OK) {
while (1);
}
/* Associate the initialized DMA handle to the UART handle */
@ -187,55 +162,14 @@ void uartReconfigure(uartPort_t *uartPort)
SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXCIEN);
}
}
return;
}
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->tx.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);
}
}
#ifdef USE_DMA
void uartTryStartTxDMA(uartPort_t *s)
{
// uartTryStartTxDMA must be protected, since it is called from
// uartWrite and handleUsartTxDma (an ISR).
ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
if (IS_DMA_ENABLED(s->txDMAResource)) {
// DMA is already in progress
@ -254,106 +188,19 @@ void uartTryStartTxDMA(uartPort_t *s)
return;
}
uint16_t size;
unsigned chunk;
uint32_t fromwhere = s->port.txBufferTail;
if (s->port.txBufferHead > s->port.txBufferTail) {
size = s->port.txBufferHead - s->port.txBufferTail;
chunk = s->port.txBufferHead - s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead;
} else {
size = s->port.txBufferSize - s->port.txBufferTail;
chunk = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
DAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
DAL_UART_Transmit_DMA(&s->Handle, (uint8_t*)s->port.txBuffer + fromwhere, chunk);
}
}
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)
{
UNUSED(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);
}
}
#endif // USE_DMA
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
#endif // USE_UART