1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +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

@ -37,9 +37,12 @@
#include "common/utils.h"
#include "io/serial.h"
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "drivers/serial.h"
#include "drivers/serial_impl.h"
#include "drivers/timer.h"
#include "serial_softserial.h"
@ -47,8 +50,6 @@
#define RX_TOTAL_BITS 10
#define TX_TOTAL_BITS 10
#define MAX_SOFTSERIAL_PORTS 2
typedef enum {
TIMER_MODE_SINGLE,
TIMER_MODE_DUAL,
@ -87,7 +88,6 @@ typedef struct softSerial_s {
uint16_t transmissionErrors;
uint16_t receiveErrors;
uint8_t softSerialPortIndex;
timerMode_e timerMode;
timerOvrHandlerRec_t overCb;
@ -95,23 +95,16 @@ typedef struct softSerial_s {
} softSerial_t;
static const struct serialPortVTable softSerialVTable; // Forward
static softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
// SERIAL_SOFTSERIAL_COUNT is fine, softserial ports must start from 1 and be continuous
static softSerial_t softSerialPorts[SERIAL_SOFTSERIAL_COUNT];
void onSerialTimerOverflow(timerOvrHandlerRec_t *cbRec, captureCompare_t capture);
void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
static void setTxSignal(softSerial_t *softSerial, uint8_t state)
typedef enum { IDLE = ENABLE, MARK = DISABLE } SerialTxState_e;
static void setTxSignal(softSerial_t *softSerial, SerialTxState_e state)
{
if (softSerial->port.options & SERIAL_INVERTED) {
state = !state;
}
if (state) {
IOHi(softSerial->txIO);
} else {
IOLo(softSerial->txIO);
}
IOWrite(softSerial->txIO, (softSerial->port.options & SERIAL_INVERTED) ? !state : state);
}
static void serialEnableCC(softSerial_t *softSerial)
@ -123,15 +116,13 @@ static void serialEnableCC(softSerial_t *softSerial)
#endif
}
// switch to receive mode
static void serialInputPortActivate(softSerial_t *softSerial)
{
if (softSerial->port.options & SERIAL_INVERTED) {
const uint8_t pinConfig = (softSerial->port.options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_PP : IOCFG_AF_PP_PD;
IOConfigGPIOAF(softSerial->rxIO, pinConfig, softSerial->timerHardware->alternateFunction);
} else {
const uint8_t pinConfig = (softSerial->port.options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_PP : IOCFG_AF_PP_UP;
IOConfigGPIOAF(softSerial->rxIO, pinConfig, softSerial->timerHardware->alternateFunction);
}
const serialPullMode_t pull = serialOptions_pull(softSerial->port.options);
const uint8_t pinConfig = ((const uint8_t[]){IOCFG_AF_PP, IOCFG_AF_PP_PD, IOCFG_AF_PP_UP})[pull];
// softserial can easily support opendrain mode, but it is not implemented
IOConfigGPIOAF(softSerial->rxIO, pinConfig, softSerial->timerHardware->alternateFunction);
softSerial->rxActive = true;
softSerial->isSearchingForStartBit = true;
@ -151,25 +142,27 @@ static void serialInputPortDeActivate(softSerial_t *softSerial)
#else
TIM_CCxCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_Disable);
#endif
IOConfigGPIO(softSerial->rxIO, IOCFG_IN_FLOATING);
IOConfigGPIO(softSerial->rxIO, IOCFG_IN_FLOATING); // leave AF mode; serialOutputPortActivate will follow immediately
softSerial->rxActive = false;
}
static void serialOutputPortActivate(softSerial_t *softSerial)
{
if (softSerial->exTimerHardware)
if (softSerial->exTimerHardware) {
IOConfigGPIOAF(softSerial->txIO, IOCFG_OUT_PP, softSerial->exTimerHardware->alternateFunction);
else
} else {
IOConfigGPIO(softSerial->txIO, IOCFG_OUT_PP);
}
}
static void serialOutputPortDeActivate(softSerial_t *softSerial)
{
if (softSerial->exTimerHardware)
if (softSerial->exTimerHardware) {
// TODO: there in no AF associated with input port
IOConfigGPIOAF(softSerial->txIO, IOCFG_IN_FLOATING, softSerial->exTimerHardware->alternateFunction);
else
} else {
IOConfigGPIO(softSerial->txIO, IOCFG_IN_FLOATING);
}
}
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
@ -183,19 +176,10 @@ static void serialTimerConfigureTimebase(const timerHardware_t *timerHardwarePtr
uint32_t clock = baseClock;
uint32_t timerPeriod;
do {
timerPeriod = clock / baud;
if (isTimerPeriodTooLarge(timerPeriod)) {
if (clock > 1) {
clock = clock / 2; // this is wrong - mhz stays the same ... This will double baudrate until ok (but minimum baudrate is < 1200)
} else {
// TODO unable to continue, unable to determine clock and timerPeriods for the given baud
}
}
} while (isTimerPeriodTooLarge(timerPeriod));
timerConfigure(timerHardwarePtr, timerPeriod, baseClock);
while (timerPeriod = clock / baud, isTimerPeriodTooLarge(timerPeriod) && clock > 1) {
clock = clock / 2; // minimum baudrate is < 1200
}
timerConfigure(timerHardwarePtr, timerPeriod, clock);
}
static void resetBuffers(softSerial_t *softSerial)
@ -211,15 +195,32 @@ static void resetBuffers(softSerial_t *softSerial)
softSerial->port.txBufferHead = 0;
}
serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options)
softSerial_t* softSerialFromIdentifier(serialPortIdentifier_e identifier)
{
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
if (identifier >= SERIAL_PORT_SOFTSERIAL1 && identifier < SERIAL_PORT_SOFTSERIAL1 + SERIAL_SOFTSERIAL_COUNT) {
return &softSerialPorts[identifier - SERIAL_PORT_SOFTSERIAL1];
}
return NULL;
}
ioTag_t tagRx = softSerialPinConfig()->ioTagRx[portIndex];
ioTag_t tagTx = softSerialPinConfig()->ioTagTx[portIndex];
serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options)
{
softSerial_t *softSerial = softSerialFromIdentifier(identifier);
if (!softSerial) {
return NULL;
}
// fill identifier early, so initialization code can use it
softSerial->port.identifier = identifier;
const timerHardware_t *timerTx = timerAllocate(tagTx, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
const timerHardware_t *timerRx = (tagTx == tagRx) ? timerTx : timerAllocate(tagRx, OWNER_SOFTSERIAL_RX, RESOURCE_INDEX(portIndex));
const int resourceIndex = serialResourceIndex(identifier);
const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
const int ownerIndex = serialOwnerIndex(identifier);
const ioTag_t tagRx = serialPinConfig()->ioTagRx[resourceIndex];
const ioTag_t tagTx = serialPinConfig()->ioTagTx[resourceIndex];
const timerHardware_t *timerTx = timerAllocate(tagTx, ownerTxRx, ownerIndex);
const timerHardware_t *timerRx = (tagTx == tagRx) ? timerTx : timerAllocate(tagRx, ownerTxRx + 1, ownerIndex);
IO_t rxIO = IOGetByTag(tagRx);
IO_t txIO = IOGetByTag(tagTx);
@ -227,7 +228,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
if (options & SERIAL_BIDIR) {
// If RX and TX pins are both assigned, we CAN use either with a timer.
// However, for consistency with hardware UARTs, we only use TX pin,
// and this pin must have a timer, and it should not be N-Channel.
// and this pin must have a timer, and it must not be N-Channel.
if (!timerTx || (timerTx->output & TIMER_OUTPUT_N_CHANNEL)) {
return NULL;
}
@ -235,10 +236,10 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->timerHardware = timerTx;
softSerial->txIO = txIO;
softSerial->rxIO = txIO;
IOInit(txIO, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
IOInit(txIO, ownerTxRx, ownerIndex);
} else {
if (mode & MODE_RX) {
// Need a pin & a timer on RX. Channel should not be N-Channel.
// Need a pin & a timer on RX. Channel must not be N-Channel.
if (!timerRx || (timerRx->output & TIMER_OUTPUT_N_CHANNEL)) {
return NULL;
}
@ -246,27 +247,29 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->rxIO = rxIO;
softSerial->timerHardware = timerRx;
if (!((mode & MODE_TX) && rxIO == txIO)) {
IOInit(rxIO, OWNER_SOFTSERIAL_RX, RESOURCE_INDEX(portIndex));
// RX only on pin
IOInit(rxIO, ownerTxRx + 1, ownerIndex);
}
}
if (mode & MODE_TX) {
// Need a pin on TX
if (!tagTx)
if (!txIO)
return NULL;
softSerial->txIO = txIO;
if (!(mode & MODE_RX)) {
// TX Simplex, must have a timer
if (!timerTx)
if (!timerTx) {
return NULL;
}
softSerial->timerHardware = timerTx;
} else {
// Duplex
// Duplex, use timerTx if available
softSerial->exTimerHardware = timerTx;
}
IOInit(txIO, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
IOInit(txIO, ownerTxRx, ownerIndex);
}
}
@ -279,8 +282,6 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
resetBuffers(softSerial);
softSerial->softSerialPortIndex = portIndex;
softSerial->transmissionErrors = 0;
softSerial->receiveErrors = 0;
@ -317,7 +318,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
if (!(options & SERIAL_BIDIR)) {
serialOutputPortActivate(softSerial);
setTxSignal(softSerial, ENABLE);
setTxSignal(softSerial, IDLE);
}
serialInputPortActivate(softSerial);
@ -332,14 +333,12 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
void processTxState(softSerial_t *softSerial)
{
uint8_t mask;
if (!softSerial->isTransmittingData) {
if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) {
// Transmit buffer empty.
// Start listening if not already in if half-duplex
// Switch to RX mode if not already listening and running in half-duplex mode
if (!softSerial->rxActive && softSerial->port.options & SERIAL_BIDIR) {
serialOutputPortDeActivate(softSerial);
serialOutputPortDeActivate(softSerial); // TODO: not necessary
serialInputPortActivate(softSerial);
}
return;
@ -352,7 +351,7 @@ void processTxState(softSerial_t *softSerial)
}
// build internal buffer, MSB = Stop Bit (1) + data bits (MSB to LSB) + start bit(0) LSB
softSerial->internalTxBuffer = (1 << (TX_TOTAL_BITS - 1)) | (byteToSend << 1);
softSerial->internalTxBuffer = (1 << (TX_TOTAL_BITS - 1)) | (byteToSend << 1) | 0;
softSerial->bitsLeftToTransmit = TX_TOTAL_BITS;
softSerial->isTransmittingData = true;
@ -365,16 +364,18 @@ void processTxState(softSerial_t *softSerial)
// and continuing here may cause bit period to decrease causing sampling errors
// at the receiver under high rates.
// Note that there will be (little less than) 1-bit delay; take it as "turn around time".
// XXX We may be able to reload counter and continue. (Future work.)
// This time is important in noninverted pulldown bidir mode (SmartAudio).
// During this period, TX pin is in IDLE state so next startbit (MARK) can be detected
// XXX Otherwise, we may be able to reload counter and continue. (Future work.)
return;
}
}
if (softSerial->bitsLeftToTransmit) {
mask = softSerial->internalTxBuffer & 1;
const bool bit = softSerial->internalTxBuffer & 1;
softSerial->internalTxBuffer >>= 1;
setTxSignal(softSerial, mask);
setTxSignal(softSerial, bit);
softSerial->bitsLeftToTransmit--;
return;
}
@ -390,8 +391,7 @@ enum {
void applyChangedBits(softSerial_t *softSerial)
{
if (softSerial->rxEdge == TRAILING) {
uint8_t bitToSet;
for (bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex; bitToSet++) {
for (unsigned bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex; bitToSet++) {
softSerial->internalRxBuffer |= 1 << bitToSet;
}
}
@ -477,12 +477,13 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
UNUSED(capture);
softSerial_t *self = container_of(cbRec, softSerial_t, edgeCb);
bool inverted = self->port.options & SERIAL_INVERTED;
if ((self->port.mode & MODE_RX) == 0) {
return;
}
const bool inverted = self->port.options & SERIAL_INVERTED;
if (self->isSearchingForStartBit) {
// Synchronize the bit timing so that it will interrupt at the center
// of the bit period.