1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +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

@ -109,9 +109,11 @@ COMMON_SRC = \
drivers/pin_pull_up_down.c \
drivers/resource.c \
drivers/serial.c \
drivers/serial_impl.c \
drivers/serial_pinconfig.c \
drivers/serial_uart.c \
drivers/serial_uart_pinconfig.c \
drivers/serial_uart_hw.c \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
@ -128,6 +130,7 @@ COMMON_SRC = \
io/beeper.c \
io/piniobox.c \
io/serial.c \
io/serial_resource.c \
io/smartaudio_protocol.c \
io/statusindicator.c \
io/tramp_protocol.c \

View file

@ -328,9 +328,10 @@ typedef enum {
} rebootTarget_e;
typedef struct serialPassthroughPort_s {
int id;
serialPortIdentifier_e id;
uint32_t baud;
unsigned mode;
portMode_e mode;
portOptions_e options;
serialPort_t *port;
} serialPassthroughPort_t;
@ -993,7 +994,7 @@ static void cliShowParseError(const char *cmdName)
static void cliShowInvalidArgumentCountError(const char *cmdName)
{
cliPrintErrorLinef(cmdName, "INVALID ARGUMENT COUNT", cmdName);
cliPrintErrorLinef(cmdName, "INVALID ARGUMENT COUNT");
}
static void cliShowArgumentRangeError(const char *cmdName, char *name, int min, int max)
@ -1278,7 +1279,7 @@ static void printSerial(dumpFlags_t dumpMask, const serialConfig_t *serialConfig
{
const char *format = "serial %d %d %ld %ld %ld %ld";
headingStr = cliPrintSectionHeading(dumpMask, false, headingStr);
for (uint32_t i = 0; i < SERIAL_PORT_COUNT; i++) {
for (unsigned i = 0; i < ARRAYLEN(serialConfig->portConfigs); i++) {
if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
continue;
};
@ -1398,24 +1399,24 @@ static void cliSerial(const char *cmdName, char *cmdline)
}
#if defined(USE_SERIAL_PASSTHROUGH)
static void cbCtrlLine(void *context, uint16_t ctrl)
static void cbCtrlLine_reset(void *context, uint16_t ctrl)
{
#ifdef USE_PINIO
int contextValue = (int)(long)context;
if (contextValue) {
pinioSet(contextValue - 1, !(ctrl & CTRL_LINE_STATE_DTR));
} else
#endif /* USE_PINIO */
UNUSED(context);
if (!(ctrl & CTRL_LINE_STATE_DTR)) {
systemReset();
}
}
static int cliParseSerialMode(const char *tok)
#ifdef USE_PINIO
static void cbCtrlLine_pinIO(void *context, uint16_t ctrl)
{
int mode = 0;
pinioSet((intptr_t)context, !(ctrl & CTRL_LINE_STATE_DTR));
}
#endif
static portMode_e cliParseSerialMode(const char *tok)
{
portMode_e mode = 0;
if (strcasestr(tok, "rx")) {
mode |= MODE_RX;
@ -1427,6 +1428,29 @@ static int cliParseSerialMode(const char *tok)
return mode;
}
static portOptions_e cliParseSerialOptions(const char *tok)
{
struct {
const char* tag;
portOptions_e val;
} map[] = {
{"Invert", SERIAL_INVERTED},
{"Stop2", SERIAL_STOPBITS_2},
{"Even", SERIAL_PARITY_EVEN},
{"Bidir", SERIAL_BIDIR},
{"Pushpull", SERIAL_BIDIR_PP},
{"Saudio", SERIAL_PULL_SMARTAUDIO},
{"Check", SERIAL_CHECK_TX},
};
portOptions_e options = 0;
for (unsigned i = 0; i < ARRAYLEN(map); i++) {
if (strstr(tok, map[i].tag) != 0) {
options |= map[i].val;
}
}
return options;
}
static void cliSerialPassthrough(const char *cmdName, char *cmdline)
{
if (isEmpty(cmdline)) {
@ -1434,64 +1458,90 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
return;
}
serialPassthroughPort_t ports[2] = { {SERIAL_PORT_NONE, 0, 0, NULL}, {cliPort->identifier, 0, 0, cliPort} };
serialPassthroughPort_t ports[2] = { {SERIAL_PORT_NONE, 0, 0, 0, NULL}, {cliPort->identifier, 0, 0, 0, cliPort} };
bool enableBaudCb = false;
int port1PinioDtr = 0;
bool port1ResetOnDtr = false;
#ifdef USE_PWM_OUTPUT
bool escSensorPassthrough = false;
#endif
char *saveptr;
char* tok = strtok_r(cmdline, " ", &saveptr);
int index = 0;
while (tok != NULL) {
switch (index) {
case 0:
if (strcasestr(tok, "esc_sensor")) {
#ifdef USE_PWM_OUTPUT
escSensorPassthrough = true;
#endif
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR);
ports[0].id = portConfig->identifier;
} else {
ports[0].id = atoi(tok);
}
break;
case 1:
ports[0].baud = atoi(tok);
break;
case 2:
ports[0].mode = cliParseSerialMode(tok);
break;
case 3:
if (strncasecmp(tok, "reset", strlen(tok)) == 0) {
port1ResetOnDtr = true;
#ifdef USE_PINIO
} else if (strncasecmp(tok, "none", strlen(tok)) == 0) {
port1PinioDtr = 0;
int port1PinioDtr = -1; // route port2 USB DTR to pinio
#endif
bool port1ResetOnDtr = false; // reset board with DTR
bool escSensorPassthrough = false;
char* nexttok = cmdline;
char* tok;
int index = 0;
while ((tok = strsep(&nexttok, " ")) != NULL) {
if (*tok == '\0') { // skip adjacent delimiters
continue;
}
unsigned portN = (index < 4) ? 0 : 1; // port1 / port2
switch (index) {
case 0: // port1 to open: esc_sensor, portName, port ID port1
case 4: // port2 to use (defaults to CLI serial if no more arguments)
{
serialPortIdentifier_e portId;
char* endptr;
if (portN == 0 && strcasestr(tok, "esc_sensor") != NULL) {
escSensorPassthrough = true;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR);
portId = portConfig ? portConfig->identifier : SERIAL_PORT_NONE;
} else if (strcasecmp(tok, "cli") == 0) {
portId = cliPort->identifier;
} else if ((portId = findSerialPortByName(tok, strcasecmp)) >= 0) {
// empty
} else if ((portId = strtol(tok, &endptr, 10)) >= 0 && *endptr == '\0') {
// empty
} else {
port1PinioDtr = atoi(tok);
if (port1PinioDtr < 0 || port1PinioDtr > PINIO_COUNT) {
cliPrintLinef("Invalid PinIO number %d", port1PinioDtr);
return ;
}
#endif /* USE_PINIO */
cliPrintLinef("Failed parsing port%d (%s)", portN + 1, tok);
return;
}
break;
case 4:
ports[1].id = atoi(tok);
ports[1].port = NULL;
break;
case 5:
ports[1].baud = atoi(tok);
break;
case 6:
ports[1].mode = cliParseSerialMode(tok);
if (portN == 1) { // port1 is specified, don't use CLI port
ports[portN].port = NULL;
}
ports[portN].id = portId;
break;
}
case 1: // baudrate
case 5: {
int baud = atoi(tok);
ports[portN].baud = baud;
break;
}
case 2: // port1 mode (rx/tx/rxtx) + options
case 6: // port2 mode + options
ports[portN].mode = cliParseSerialMode(tok);
ports[portN].options = cliParseSerialOptions(tok);
break;
case 3: // DTR action
if (strcasecmp(tok, "reset") == 0) {
port1ResetOnDtr = true;
break;
}
if (strcasecmp(tok, "none") == 0) {
break;
}
#ifdef USE_PINIO
port1PinioDtr = atoi(tok);
if (port1PinioDtr < 0 || port1PinioDtr >= PINIO_COUNT) {
cliPrintLinef("Invalid PinIO number %d", port1PinioDtr);
return;
}
#endif /* USE_PINIO */
break;
default:
cliPrintLinef("Unexpected argument %d (%s)", index + 1, tok);
return;
}
index++;
tok = strtok_r(NULL, " ", &saveptr);
}
for (unsigned i = 0; i < ARRAYLEN(ports); i++) {
if (findSerialPortIndexByIdentifier(ports[i].id) < 0) {
cliPrintLinef("Invalid port%d %d", i + 1, ports[i].id);
return;
} else {
cliPrintLinef("Port%d: %s", i + 1, serialName(ports[i].id, "<invalid>"));
}
}
// Port checks
@ -1500,74 +1550,70 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
return ;
}
for (int i = 0; i < 2; i++) {
if (findSerialPortIndexByIdentifier(ports[i].id) == -1) {
cliPrintLinef("Invalid port%d %d", i + 1, ports[i].id);
return ;
} else {
cliPrintLinef("Port%d: %d ", i + 1, ports[i].id);
}
}
if (ports[0].baud == 0 && ports[1].id == SERIAL_PORT_USB_VCP) {
enableBaudCb = true;
}
for (int i = 0; i < 2; i++) {
serialPort_t **port = &(ports[i].port);
if (*port != NULL) {
serialPassthroughPort_t* cfg = &ports[i];
if (cfg->port != NULL) { // port already selected, don't touch it (used when port2 defaults to cli)
continue;
}
int portIndex = i + 1;
serialPortUsage_t *portUsage = findSerialPortUsageByIdentifier(ports[i].id);
serialPortUsage_t *portUsage = findSerialPortUsageByIdentifier(cfg->id);
if (!portUsage || portUsage->serialPort == NULL) {
bool isUseDefaultBaud = false;
if (ports[i].baud == 0) {
// serial port is not open yet
const bool isUseDefaultBaud = cfg->baud == 0;
if (isUseDefaultBaud) {
// Set default baud
ports[i].baud = 57600;
isUseDefaultBaud = true;
cfg->baud = 57600;
}
if (!ports[i].mode) {
ports[i].mode = MODE_RXTX;
if (!cfg->mode) {
cliPrintLinef("Using RXTX mode as default");
cfg->mode = MODE_RXTX;
}
*port = openSerialPort(ports[i].id, FUNCTION_NONE, NULL, NULL,
ports[i].baud, ports[i].mode,
SERIAL_NOT_INVERTED);
if (!*port) {
if (cfg->options) {
cliPrintLinef("Port%d: using options 0x%x",
portIndex, cfg->options);
}
cfg->port = openSerialPort(cfg->id, FUNCTION_NONE,
NULL, NULL, // rxCallback
cfg->baud, cfg->mode, cfg->options);
if (!cfg->port) {
cliPrintLinef("Port%d could not be opened.", portIndex);
return;
}
if (isUseDefaultBaud) {
cliPrintf("Port%d opened, default baud = %d.\r\n", portIndex, ports[i].baud);
} else {
cliPrintf("Port%d opened, baud = %d.\r\n", portIndex, ports[i].baud);
}
cliPrintf("Port%d opened, %sbaud = %d.\r\n", portIndex, isUseDefaultBaud ? "default ":"", cfg->baud);
} else {
*port = portUsage->serialPort;
cfg->port = portUsage->serialPort;
// If the user supplied a mode, override the port's mode, otherwise
// leave the mode unchanged. serialPassthrough() handles one-way ports.
// Set the baud rate if specified
if (ports[i].baud) {
cliPrintf("Port%d is already open, setting baud = %d.\r\n", portIndex, ports[i].baud);
serialSetBaudRate(*port, ports[i].baud);
} else {
cliPrintf("Port%d is already open, baud = %d.\r\n", portIndex, (*port)->baudRate);
if (cfg->baud) {
serialSetBaudRate(cfg->port, cfg->baud);
}
cliPrintLinef("Port%d is already open, %sbaud = %d.", portIndex, cfg->baud ? "new " : "", cfg->port->baudRate);
if (cfg->mode && cfg->port->mode != cfg->mode) {
cliPrintLinef("Port%d mode changed from %d to %d.",
portIndex, cfg->port->mode, cfg->mode);
serialSetMode(cfg->port, cfg->mode);
}
if (ports[i].mode && (*port)->mode != ports[i].mode) {
cliPrintf("Port%d mode changed from %d to %d.\r\n",
portIndex, (*port)->mode, ports[i].mode);
serialSetMode(*port, ports[i].mode);
if (cfg->options) {
cliPrintLinef("Port%d is open, can't change options from 0x%x to 0x%x",
portIndex, cfg->port->options, cfg->options);
}
// If this port has a rx callback associated we need to remove it now.
// Otherwise no data will be pushed in the serial port buffer!
if ((*port)->rxCallback) {
(*port)->rxCallback = NULL;
if (cfg->port->rxCallback) {
cliPrintLinef("Port%d: Callback removed", portIndex);
cfg->port->rxCallback = NULL;
}
}
}
@ -1580,20 +1626,26 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
serialSetBaudRateCb(ports[1].port, serialSetBaudRate, ports[0].port);
}
char *resetMessage = "";
const char *resetMessage = "";
if (port1ResetOnDtr && ports[1].id == SERIAL_PORT_USB_VCP) {
resetMessage = "or drop DTR ";
}
cliPrintLinef("Forwarding, power cycle %sto exit.", resetMessage);
if ((ports[1].id == SERIAL_PORT_USB_VCP) && (port1ResetOnDtr
if ((ports[1].id == SERIAL_PORT_USB_VCP)) {
do {
if (port1ResetOnDtr) {
serialSetCtrlLineStateCb(ports[1].port, cbCtrlLine_reset, NULL);
break;
}
#ifdef USE_PINIO
|| port1PinioDtr
if (port1PinioDtr >= 0) {
serialSetCtrlLineStateCb(ports[1].port, cbCtrlLine_pinIO, (void *)(intptr_t)(port1PinioDtr));
break;
}
#endif /* USE_PINIO */
)) {
// Register control line state callback
serialSetCtrlLineStateCb(ports[0].port, cbCtrlLine, (void *)(intptr_t)(port1PinioDtr));
} while (0);
}
// XXX Review ESC pass through under refactored motor handling
@ -1608,7 +1660,7 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
const timerHardware_t *timerHardware = timerGetConfiguredByTag(tag);
if (timerHardware) {
IO_t io = IOGetByTag(tag);
IOInit(io, OWNER_MOTOR, 0);
IOInit(io, OWNER_MOTOR, i);
IOConfigGPIO(io, IOCFG_OUT_PP);
if (timerHardware->output & TIMER_OUTPUT_INVERTED) {
IOLo(io);
@ -5022,7 +5074,7 @@ typedef struct {
const cliResourceValue_t resourceTable[] = {
#if defined(USE_BEEPER)
DEFS( OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, beeperDevConfig_t, ioTag) ,
DEFS( OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, beeperDevConfig_t, ioTag ),
#endif
DEFA( OWNER_MOTOR, PG_MOTOR_CONFIG, motorConfig_t, dev.ioTags[0], MAX_SUPPORTED_MOTORS ),
#if defined(USE_SERVOS)
@ -5041,20 +5093,21 @@ const cliResourceValue_t resourceTable[] = {
#if defined(USE_LED_STRIP)
DEFS( OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, ledStripConfig_t, ioTag ),
#endif
#ifdef USE_UART
DEFA( OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[0], SERIAL_UART_COUNT ),
DEFA( OWNER_SERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[0], SERIAL_UART_COUNT ),
#if defined(USE_UART)
DEFA( OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT ),
DEFA( OWNER_SERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT ),
#endif
#ifdef USE_INVERTER
DEFA( OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagInverter[0], SERIAL_PORT_MAX_INDEX ),
#if defined(USE_INVERTER)
DEFA( OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagInverter[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT ),
// LPUART and SOFTSERIAL don't need external inversion
#endif
#if defined(USE_SOFTSERIAL)
DEFA( OWNER_SOFTSERIAL_TX, PG_SOFTSERIAL_PIN_CONFIG, softSerialPinConfig_t, ioTagTx[0], SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_RX, PG_SOFTSERIAL_PIN_CONFIG, softSerialPinConfig_t, ioTagRx[0], SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_SOFTSERIAL_OFFSET], RESOURCE_SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_SOFTSERIAL_OFFSET], RESOURCE_SOFTSERIAL_COUNT ),
#endif
#ifdef USE_LPUART1
DEFA( OWNER_LPUART_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[SERIAL_UART_COUNT], SERIAL_LPUART_COUNT ),
DEFA( OWNER_LPUART_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[SERIAL_UART_COUNT], SERIAL_LPUART_COUNT ),
#if defined(USE_LPUART)
DEFA( OWNER_LPUART_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_LPUART_OFFSET], RESOURCE_LPUART_COUNT ),
DEFA( OWNER_LPUART_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_LPUART_OFFSET], RESOURCE_LPUART_COUNT ),
#endif
#ifdef USE_I2C
DEFW( OWNER_I2C_SCL, PG_I2C_CONFIG, i2cConfig_t, ioTagScl, I2CDEV_COUNT ),
@ -5163,10 +5216,10 @@ const cliResourceValue_t resourceTable[] = {
#undef DEFA
#undef DEFW
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
static ioTag_t* getIoTag(const cliResourceValue_t value, uint8_t index)
{
const pgRegistry_t* rec = pgFind(value.pgn);
return CONST_CAST(ioTag_t *, rec->address + value.stride * index + value.offset);
return (ioTag_t *)(rec->address + value.stride * index + value.offset);
}
static void printResource(dumpFlags_t dumpMask, const char *headingStr)
@ -5321,6 +5374,7 @@ typedef struct dmaoptEntry_s {
// DEFS : Single entry
// DEFA : Array of uint8_t (stride = 1)
// DEFW : Wider stride case; array of structs.
// DEFW_OFS: array of structs, starting at offset ofs
#define DEFS(device, peripheral, pgn, type, member) \
{ device, peripheral, pgn, 0, offsetof(type, member), 0, MASK_IGNORED }
@ -5329,7 +5383,10 @@ typedef struct dmaoptEntry_s {
{ device, peripheral, pgn, sizeof(uint8_t), offsetof(type, member), max, mask }
#define DEFW(device, peripheral, pgn, type, member, max, mask) \
{ device, peripheral, pgn, sizeof(type), offsetof(type, member), max, mask }
DEFW_OFS(device, peripheral, pgn, type, member, 0, max, mask)
#define DEFW_OFS(device, peripheral, pgn, type, member, ofs, max, mask) \
{ device, peripheral, pgn, sizeof(type), offsetof(type, member) + (ofs) * sizeof(type), max, mask }
dmaoptEntry_t dmaoptEntryTable[] = {
DEFW("SPI_SDO", DMA_PERIPH_SPI_SDO, PG_SPI_PIN_CONFIG, spiPinConfig_t, txDmaopt, SPIDEV_COUNT, MASK_IGNORED),
@ -5339,8 +5396,14 @@ dmaoptEntry_t dmaoptEntryTable[] = {
DEFW("SPI_RX", DMA_PERIPH_SPI_SDI, PG_SPI_PIN_CONFIG, spiPinConfig_t, rxDmaopt, SPIDEV_COUNT, MASK_IGNORED),
DEFA("ADC", DMA_PERIPH_ADC, PG_ADC_CONFIG, adcConfig_t, dmaopt, ADCDEV_COUNT, MASK_IGNORED),
DEFS("SDIO", DMA_PERIPH_SDIO, PG_SDIO_CONFIG, sdioConfig_t, dmaopt),
DEFW("UART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, UARTDEV_CONFIG_MAX, MASK_IGNORED),
DEFW("UART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, UARTDEV_CONFIG_MAX, MASK_IGNORED),
#ifdef USE_UART
DEFW_OFS("UART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, RESOURCE_UART_OFFSET, RESOURCE_UART_COUNT, MASK_IGNORED),
DEFW_OFS("UART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, RESOURCE_UART_OFFSET, RESOURCE_UART_COUNT, MASK_IGNORED),
#endif
#ifdef USE_LPUART
DEFW_OFS("LPUART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, RESOURCE_LPUART_OFFSET, RESOURCE_LPUART_COUNT, MASK_IGNORED),
DEFW_OFS("LPUART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, RESOURCE_LPUART_OFFSET, RESOURCE_LPUART_COUNT, MASK_IGNORED),
#endif
#if defined(STM32H7) || defined(STM32G4)
DEFW("TIMUP", DMA_PERIPH_TIMUP, PG_TIMER_UP_CONFIG, timerUpConfig_t, dmaopt, HARDWARE_TIMER_DEFINITION_COUNT, TIMUP_TIMERS),
#endif
@ -6071,7 +6134,7 @@ static void cliResource(const char *cmdName, char *cmdline)
}
pch = strtok_r(NULL, " ", &saveptr);
int index = atoi(pch);
int index = pch ? atoi(pch) : 0;
if (resourceTable[resourceIndex].maxIndex > 0 || index > 0) {
if (index <= 0 || index > RESOURCE_VALUE_MAX_INDEX(resourceTable[resourceIndex].maxIndex)) {
@ -6083,11 +6146,13 @@ static void cliResource(const char *cmdName, char *cmdline)
pch = strtok_r(NULL, " ", &saveptr);
}
ioTag_t *tag = getIoTag(resourceTable[resourceIndex], index);
ioTag_t *resourceTag = getIoTag(resourceTable[resourceIndex], index);
if (strlen(pch) > 0) {
if (strToPin(pch, tag)) {
if (*tag == IO_TAG_NONE) {
if (pch && strlen(pch) > 0) {
ioTag_t tag;
if (strToPin(pch, &tag)) {
if (!tag) {
*resourceTag = tag;
#ifdef MINIMAL_CLI
cliPrintLine("Freed");
#else
@ -6095,9 +6160,10 @@ static void cliResource(const char *cmdName, char *cmdline)
#endif
return;
} else {
ioRec_t *rec = IO_Rec(IOGetByTag(*tag));
ioRec_t *rec = IO_Rec(IOGetByTag(tag));
if (rec) {
resourceCheck(resourceIndex, index, *tag);
*resourceTag = tag;
resourceCheck(resourceIndex, index, tag);
#ifdef MINIMAL_CLI
cliPrintLinef(" %c%02d set", IO_GPIOPortIdx(rec) + 'A', IO_GPIOPinIdx(rec));
#else
@ -6106,12 +6172,18 @@ static void cliResource(const char *cmdName, char *cmdline)
} else {
cliShowParseError(cmdName);
}
return;
}
} else {
cliPrintErrorLinef(cmdName, "Failed to parse '%s' as pin", pch);
}
} else {
ioTag_t tag = *resourceTag;
char ioName[5];
if (tag) {
tfp_sprintf(ioName, "%c%02d", IO_GPIOPortIdxByTag(tag) + 'A', IO_GPIOPinIdxByTag(tag));
}
cliPrintLinef("# resource %s %d %s", ownerNames[resourceTable[resourceIndex].owner], RESOURCE_INDEX(index), tag ? ioName : "NONE");
}
cliShowParseError(cmdName);
}
#endif

View file

@ -33,7 +33,7 @@
#include "printf_serial.h"
#ifdef SERIAL_PORT_COUNT
#if SERIAL_PORT_COUNT > 0
static serialPort_t *printfSerialPort;

View file

@ -75,6 +75,11 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
#define BITCOUNT(x) (((BX_(x)+(BX_(x)>>4)) & 0x0F0F0F0F) % 255)
#define BX_(x) ((x) - (((x)>>1)&0x77777777) - (((x)>>2)&0x33333333) - (((x)>>3)&0x11111111))
static inline int popcount(unsigned x) { return __builtin_popcount(x); }
static inline int popcount32(uint32_t x) { return __builtin_popcount(x); }
static inline int popcount64(uint64_t x) { return __builtin_popcountll(x); }
/*
* https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ

View file

@ -416,11 +416,16 @@ static void validateAndFixConfig(void)
if (systemConfig()->configurationState == CONFIGURATION_STATE_UNCONFIGURED) {
// enable some compiled-in features by default
uint32_t autoFeatures =
FEATURE_OSD | FEATURE_LED_STRIP
#if defined(SOFTSERIAL1_RX_PIN) || defined(SOFTSERIAL2_RX_PIN) || defined(SOFTSERIAL1_TX_PIN) || defined(SOFTSERIAL2_TX_PIN)
| FEATURE_SOFTSERIAL
FEATURE_OSD | FEATURE_LED_STRIP;
#if defined(USE_SOFTSERIAL)
// enable softserial if at least one pin is configured
for (unsigned i = RESOURCE_SOFTSERIAL_OFFSET; i < RESOURCE_SOFTSERIAL_OFFSET + RESOURCE_SOFTSERIAL_COUNT; i++) {
if (serialPinConfig()->ioTagTx[i] || serialPinConfig()->ioTagRx[i]) {
autoFeatures |= FEATURE_SOFTSERIAL;
break;
}
}
#endif
;
featureEnableImmediate(autoFeatures & featuresSupportedByBuild);
}
@ -530,12 +535,11 @@ static void validateAndFixConfig(void)
// Find the first serial port on which MSP Displayport is enabled
displayPortMspSetSerial(SERIAL_PORT_NONE);
for (uint8_t serialPort = 0; serialPort < SERIAL_PORT_COUNT; serialPort++) {
const serialPortConfig_t *portConfig = &serialConfig()->portConfigs[serialPort];
if (portConfig &&
(portConfig->identifier != SERIAL_PORT_USB_VCP) &&
((portConfig->functionMask & (FUNCTION_VTX_MSP | FUNCTION_MSP)) == (FUNCTION_VTX_MSP | FUNCTION_MSP))) {
for (const serialPortConfig_t *portConfig = serialConfig()->portConfigs;
portConfig < ARRAYEND(serialConfig()->portConfigs);
portConfig++) {
if ((portConfig->identifier != SERIAL_PORT_USB_VCP)
&& ((portConfig->functionMask & (FUNCTION_VTX_MSP | FUNCTION_MSP)) == (FUNCTION_VTX_MSP | FUNCTION_MSP))) {
displayPortMspSetSerial(portConfig->identifier);
break;
}

View file

@ -50,7 +50,7 @@ typedef enum {
DMA_PERIPH_SPI_SDI,
DMA_PERIPH_ADC,
DMA_PERIPH_SDIO,
DMA_PERIPH_UART_TX,
DMA_PERIPH_UART_TX, // LPUART is handled as UART
DMA_PERIPH_UART_RX,
DMA_PERIPH_TIMUP,
} dmaPeripheral_e;

View file

@ -25,33 +25,40 @@
#ifdef USE_INVERTER
#include "io/serial.h" // For SERIAL_PORT_IDENTIFIER_TO_INDEX
#include "io/serial.h"
#include "drivers/io.h"
#include "drivers/serial.h"
#include "drivers/serial_impl.h"
#include "inverter.h"
static const serialPinConfig_t *pSerialPinConfig;
static void inverterSet(int identifier, bool on)
static IO_t findInverterPin(serialPortIdentifier_e identifier)
{
IO_t pin = IOGetByTag(pSerialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(identifier)]);
if (pin) {
IOWrite(pin, on);
const int resourceIndex = serialResourceIndex(identifier);
if (resourceIndex >= 0 && resourceIndex < (int)ARRAYLEN(pSerialPinConfig->ioTagInverter)) {
return IOGetByTag(pSerialPinConfig->ioTagInverter[resourceIndex]);
} else {
return NULL;
}
}
static void initInverter(int identifier)
static void inverterSet(IO_t pin, bool on)
{
int uartIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(identifier);
IO_t pin = IOGetByTag(pSerialPinConfig->ioTagInverter[uartIndex]);
IOWrite(pin, on);
}
static void initInverter(serialPortIdentifier_e identifier)
{
IO_t pin = findInverterPin(identifier);
if (pin) {
IOInit(pin, OWNER_INVERTER, RESOURCE_INDEX(uartIndex));
const int ownerIndex = serialOwnerIndex(identifier);
// only UART supports inverter, so OWNER_INVERTER+ownerIndex does work
IOInit(pin, OWNER_INVERTER, ownerIndex);
IOConfigGPIO(pin, IOCFG_OUT_PP);
inverterSet(identifier, false);
inverterSet(pin, false);
}
}
@ -59,73 +66,18 @@ void initInverters(const serialPinConfig_t *serialPinConfigToUse)
{
pSerialPinConfig = serialPinConfigToUse;
#ifdef USE_UART1
initInverter(SERIAL_PORT_USART1);
#endif
#ifdef USE_UART2
initInverter(SERIAL_PORT_USART2);
#endif
#ifdef USE_UART3
initInverter(SERIAL_PORT_USART3);
#endif
#ifdef USE_UART4
initInverter(SERIAL_PORT_UART4);
#endif
#ifdef USE_UART5
initInverter(SERIAL_PORT_UART5);
#endif
#ifdef USE_UART6
initInverter(SERIAL_PORT_USART6);
#endif
for (unsigned i = 0; i < ARRAYLEN(serialPortIdentifiers); i++) {
// it is safe to pass port without inverter
initInverter(serialPortIdentifiers[i]);
}
}
void enableInverter(USART_TypeDef *USARTx, bool on)
void enableInverter(serialPortIdentifier_e identifier, bool on)
{
int identifier = SERIAL_PORT_NONE;
#ifdef USE_UART1
if (USARTx == USART1) {
identifier = SERIAL_PORT_USART1;
}
#endif
#ifdef USE_UART2
if (USARTx == USART2) {
identifier = SERIAL_PORT_USART2;
}
#endif
#ifdef USE_UART3
if (USARTx == USART3) {
identifier = SERIAL_PORT_USART3;
}
#endif
#ifdef USE_UART4
if (USARTx == UART4) {
identifier = SERIAL_PORT_UART4;
}
#endif
#ifdef USE_UART5
if (USARTx == UART5) {
identifier = SERIAL_PORT_UART5;
}
#endif
#ifdef USE_UART6
if (USARTx == USART6) {
identifier = SERIAL_PORT_USART6;
}
#endif
if (identifier != SERIAL_PORT_NONE) {
inverterSet(identifier, on);
const IO_t pin = findInverterPin(identifier);
if (pin) {
inverterSet(pin, on);
}
}
#endif // USE_INVERTER

View file

@ -21,7 +21,7 @@
#pragma once
#include "drivers/serial.h"
#include "io/serial.h"
void initInverters(const serialPinConfig_t *serialPinConfigToUse);
void enableInverter(USART_TypeDef *USARTx, bool on);
void enableInverter(serialPortIdentifier_e portId, bool on);

View file

@ -174,7 +174,7 @@ IO_t IOGetByTag(ioTag_t tag)
return NULL;
}
// count bits before this pin on single port
int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
int offset = popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
// and add port offset
offset += ioDefUsedOffset[portIdx];
return ioRecs + offset;

View file

@ -38,7 +38,10 @@
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
//speed is packed inside modebits 5 and 2,
// speed is packed between modebits 4 and 1,
// 7 6 5 4 3 2 1 0
// 0 <pupd-1> <pupd-0> <mode-4> <speed-1> <speed-0> <mode-1> <mode-0>
// mode-4 is equivalent to STM32F4 otype (pushpull/od)
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
@ -86,7 +89,7 @@
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_NONE)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE , 0, GPIO_PULL_UP)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#elif defined(APM32F4)

View file

@ -77,19 +77,23 @@
#define NVIC_PRIO_SPI_DMA NVIC_BUILD_PRIORITY(0, 0)
#define NVIC_PRIO_SDIO_DMA NVIC_BUILD_PRIORITY(0, 0)
#ifdef USE_HAL_DRIVER
// utility macros to join/split priority
#ifdef USE_HAL_DRIVER
#define NVIC_PRIORITY_GROUPING NVIC_PRIORITYGROUP_2
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING)))))<<4)&0xf0)
#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING))))>>4)
#define NVIC_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING))))>>4)
#elif defined(USE_ATBSP_DRIVER)
#define NVIC_PRIORITY_GROUPING NVIC_PRIORITY_GROUP_2
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING)))))<<4)&0xf0)
#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING))))>>4)
#define NVIC_PRIORITY_SUB(prio) (((prio)&((0x0f>>(7-(NVIC_PRIORITY_GROUPING)))<<4))>>4)
#else
// utility macros to join/split priority
#define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_2
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0)
#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING>>8))))>>4)

View file

@ -60,8 +60,7 @@ void pinioInit(const pinioConfig_t *pinioConfig)
break;
}
if (pinioConfig->config[i] & PINIO_CONFIG_OUT_INVERTED)
{
if (pinioConfig->config[i] & PINIO_CONFIG_OUT_INVERTED) {
pinioRuntime[i].inverted = true;
IOHi(io);
pinioRuntime[i].state = true;
@ -76,7 +75,10 @@ void pinioInit(const pinioConfig_t *pinioConfig)
void pinioSet(int index, bool on)
{
bool newState = on ^ pinioRuntime[index].inverted;
if (index < 0 || index >= PINIO_COUNT) {
return;
}
const bool newState = on ^ pinioRuntime[index].inverted;
if (newState != pinioRuntime[index].state) {
IOWrite(pinioRuntime[index].io, newState);
pinioRuntime[index].state = newState;

View file

@ -34,8 +34,8 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"ADC_CURR",
"ADC_EXT",
"ADC_RSSI",
"SERIAL_TX",
"SERIAL_RX",
[OWNER_SERIAL_TX] = "SERIAL_TX",
[OWNER_SERIAL_RX] = "SERIAL_RX",
"DEBUG",
"TIMER",
"SONAR_TRIGGER",
@ -111,9 +111,9 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"SWD",
"RX_SPI_EXPRESSLRS_RESET",
"RX_SPI_EXPRESSLRS_BUSY",
"SOFTSERIAL_TX",
"SOFTSERIAL_RX",
"LPUART_TX",
"LPUART_RX",
[OWNER_SOFTSERIAL_TX] = "SOFTSERIAL_TX",
[OWNER_SOFTSERIAL_RX] = "SOFTSERIAL_RX",
[OWNER_LPUART_TX] = "LPUART_TX",
[OWNER_LPUART_RX] = "LPUART_RX",
"GYRO_CLKIN",
};

View file

@ -32,7 +32,7 @@ typedef enum {
OWNER_ADC_CURR,
OWNER_ADC_EXT,
OWNER_ADC_RSSI,
OWNER_SERIAL_TX,
OWNER_SERIAL_TX, // TX must be just before RX
OWNER_SERIAL_RX,
OWNER_PINDEBUG,
OWNER_TIMER,
@ -109,9 +109,9 @@ typedef enum {
OWNER_SWD,
OWNER_RX_SPI_EXPRESSLRS_RESET,
OWNER_RX_SPI_EXPRESSLRS_BUSY,
OWNER_SOFTSERIAL_TX,
OWNER_SOFTSERIAL_TX, // TX must be just before RX
OWNER_SOFTSERIAL_RX,
OWNER_LPUART_TX,
OWNER_LPUART_TX, // TX must be just before RX
OWNER_LPUART_RX,
OWNER_GYRO_CLKIN,
OWNER_TOTAL_COUNT

View file

@ -23,6 +23,7 @@
#include "platform.h"
#include "io/serial.h"
#include "serial.h"
void serialPrint(serialPort_t *instance, const char *str)
@ -130,3 +131,4 @@ void serialWriteBufShim(void *instance, const uint8_t *data, int count)
{
serialWriteBuf((serialPort_t *)instance, data, count);
}

View file

@ -23,8 +23,7 @@
#include "drivers/io.h"
#include "drivers/io_types.h"
#include "drivers/resource.h"
// TODO(hertz@): uncomment and use UARTDevice_e::MAX_UARTDEV
// #include "drivers/serial_uart.h"
#include "drivers/serial_resource.h"
#include "pg/pg.h"
@ -45,18 +44,27 @@ typedef enum {
SERIAL_BIDIR = 1 << 3,
/*
* Note on SERIAL_BIDIR_PP
* Note on SERIAL_BIDIR_PP *on some MCU families*
* With SERIAL_BIDIR_PP, the very first start bit of back-to-back bytes
* is lost and the first data byte will be lost by a framing error.
* To ensure the first start bit to be sent, prepend a zero byte (0x00)
* to actual data bytes.
*/
SERIAL_BIDIR_OD = 0 << 4,
SERIAL_BIDIR_PP = 1 << 4,
SERIAL_BIDIR_NOPULL = 1 << 5, // disable pulls in BIDIR RX mode
SERIAL_BIDIR_PP_PD = 1 << 6, // PP mode, normall inverted, but with PullDowns, to fix SA after bidir issue fixed (#10220)
// output configuration in BIDIR non-inverted mode
// pushpull is used in UNIDIR or inverted mode by default
// SERIAL_BIDIR must be specified explicitly
SERIAL_BIDIR_OD = 0 << 4, // default in BIDIR non-inverted mode
SERIAL_BIDIR_PP = 1 << 4, // force pushpull
SERIAL_PULL_DEFAULT = 0 << 5, // pulldown in inverted mode, pullup otherwise
SERIAL_PULL_NONE = 1 << 5, // disable pulls in RX or opendrain TX mode
// option for Smartaudio serial port - line is in MARK state when idle - break condition.
// DO NOT USE unless absolutely necessary
// SERIAL_PULL_NONE has precedence
SERIAL_PULL_SMARTAUDIO = 1 << 6, // set PULLDOWN on RX, even when not inverted.
// If this option is set then switch the TX line to input when not in use to detect it being pulled low
// (and prevent powering external device by TX pin)
SERIAL_CHECK_TX = 1 << 7,
} portOptions_e;
@ -90,32 +98,19 @@ typedef struct serialPort_s {
serialIdleCallbackPtr idleCallback;
uint8_t identifier;
uint8_t identifier; // actually serialPortIdentifier_e; avoid circular header dependency
} serialPort_t;
#define SERIAL_PORT_MAX_INDEX 11
#define SERIAL_UART_COUNT 10
#define SERIAL_LPUART_COUNT 1
typedef struct serialPinConfig_s {
ioTag_t ioTagTx[SERIAL_PORT_MAX_INDEX];
ioTag_t ioTagRx[SERIAL_PORT_MAX_INDEX];
ioTag_t ioTagInverter[SERIAL_PORT_MAX_INDEX];
ioTag_t ioTagTx[RESOURCE_SERIAL_COUNT];
ioTag_t ioTagRx[RESOURCE_SERIAL_COUNT];
#ifdef USE_INVERTER
ioTag_t ioTagInverter[RESOURCE_UART_COUNT]; // this array is only for UARTs.
#endif
} serialPinConfig_t;
PG_DECLARE(serialPinConfig_t, serialPinConfig);
#if defined(USE_SOFTSERIAL)
#define SOFTSERIAL_COUNT 2
typedef struct softSerialPinConfig_s {
ioTag_t ioTagTx[SOFTSERIAL_COUNT];
ioTag_t ioTagRx[SOFTSERIAL_COUNT];
} softSerialPinConfig_t;
PG_DECLARE(softSerialPinConfig_t, softSerialPinConfig);
#endif
struct serialPortVTable {
void (*serialWrite)(serialPort_t *instance, uint8_t ch);

View file

@ -0,0 +1,39 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "io/serial.h"
#include "serial.h"
#include "serial_impl.h"
// convert options into pin pull mode (up/down/none)
serialPullMode_t serialOptions_pull(portOptions_e options)
{
// handle SmartAudio first - different SA versions need different values
// add more cases here if necessary
if (options & SERIAL_PULL_SMARTAUDIO) {
#ifdef USE_SMARTAUDIO_NOPULLDOWN
return serialPullNone;
#else
return serialPullDown;
#endif
}
if (options & SERIAL_PULL_NONE) {
return serialPullNone; // explicit nopull
} else if (options & SERIAL_INVERTED) {
return serialPullDown;
} else {
return serialPullUp;
}
}
// is pushPull mode necessary
bool serialOptions_pushPull(portOptions_e options)
{
return options & (SERIAL_INVERTED | SERIAL_BIDIR_PP);
}

View file

@ -0,0 +1,39 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdbool.h>
/*
* common functions related to serial port implementation
*/
// owner of Tx pin (+1 for Rx)
resourceOwner_e serialOwnerTxRx(serialPortIdentifier_e identifier);
// index for given owner
int serialOwnerIndex(serialPortIdentifier_e identifier);
typedef enum { serialPullNone = 0, serialPullDown = 1, serialPullUp = 2 } serialPullMode_t;
serialPullMode_t serialOptions_pull(portOptions_e options);
bool serialOptions_pushPull(portOptions_e options);

View file

@ -34,159 +34,7 @@
#include "pg/pg_ids.h"
// Backward compatibility for existing targets
// Default pin (NONE).
#ifdef USE_UART1
# if !defined(UART1_RX_PIN)
# define UART1_RX_PIN NONE
# endif
# if !defined(UART1_TX_PIN)
# define UART1_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART1)
# define INVERTER_PIN_UART1 NONE
# endif
#endif
#ifdef USE_UART2
# if !defined(UART2_RX_PIN)
# define UART2_RX_PIN NONE
# endif
# if !defined(UART2_TX_PIN)
# define UART2_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART2)
# define INVERTER_PIN_UART2 NONE
# endif
#endif
#ifdef USE_UART3
# if !defined(UART3_RX_PIN)
# define UART3_RX_PIN NONE
# endif
# if !defined(UART3_TX_PIN)
# define UART3_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART3)
# define INVERTER_PIN_UART3 NONE
# endif
#endif
#ifdef USE_UART4
# if !defined(UART4_RX_PIN)
# define UART4_RX_PIN NONE
# endif
# if !defined(UART4_TX_PIN)
# define UART4_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART4)
# define INVERTER_PIN_UART4 NONE
# endif
#endif
#ifdef USE_UART5
# if !defined(UART5_RX_PIN)
# define UART5_RX_PIN NONE
# endif
# if !defined(UART5_TX_PIN)
# define UART5_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART5)
# define INVERTER_PIN_UART5 NONE
# endif
#endif
#ifdef USE_UART6
# if !defined(UART6_RX_PIN)
# define UART6_RX_PIN NONE
# endif
# if !defined(UART6_TX_PIN)
# define UART6_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART6)
# define INVERTER_PIN_UART6 NONE
# endif
#endif
#ifdef USE_UART7
# if !defined(UART7_RX_PIN)
# define UART7_RX_PIN NONE
# endif
# if !defined(UART7_TX_PIN)
# define UART7_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART7)
# define INVERTER_PIN_UART7 NONE
# endif
#endif
#ifdef USE_UART8
# if !defined(UART8_RX_PIN)
# define UART8_RX_PIN NONE
# endif
# if !defined(UART8_TX_PIN)
# define UART8_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART8)
# define INVERTER_PIN_UART8 NONE
# endif
#endif
#ifdef USE_UART9
# if !defined(UART9_RX_PIN)
# define UART9_RX_PIN NONE
# endif
# if !defined(UART9_TX_PIN)
# define UART9_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART9)
# define INVERTER_PIN_UART9 NONE
# endif
#endif
#ifdef USE_UART10
# if !defined(UART10_RX_PIN)
# define UART10_RX_PIN NONE
# endif
# if !defined(UART10_TX_PIN)
# define UART10_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_UART10)
# define INVERTER_PIN_UART10 NONE
# endif
#endif
#ifdef USE_LPUART1
# if !defined(LPUART1_RX_PIN)
# define LPUART1_RX_PIN NONE
# endif
# if !defined(LPUART1_TX_PIN)
# define LPUART1_TX_PIN NONE
# endif
# if !defined(INVERTER_PIN_LPUART1)
# define INVERTER_PIN_LPUART1 NONE
# endif
#endif
#ifdef USE_SOFTSERIAL
# if !defined(SOFTSERIAL1_RX_PIN)
# define SOFTSERIAL1_RX_PIN NONE
# endif
# if !defined(SOFTSERIAL1_TX_PIN)
# define SOFTSERIAL1_TX_PIN NONE
# endif
# if !defined(SOFTSERIAL2_RX_PIN)
# define SOFTSERIAL2_RX_PIN NONE
# endif
# if !defined(SOFTSERIAL2_TX_PIN)
# define SOFTSERIAL2_TX_PIN NONE
# endif
#endif
#if defined(USE_UART) || defined(USE_SOFTSERIAL)
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
typedef struct serialDefaultPin_s {
serialPortIdentifier_e ident;
ioTag_t rxIO, txIO, inverterIO;
@ -224,7 +72,13 @@ static const serialDefaultPin_t serialDefaultPin[] = {
{ SERIAL_PORT_USART10, IO_TAG(UART10_RX_PIN), IO_TAG(UART10_TX_PIN), IO_TAG(INVERTER_PIN_UART10) },
#endif
#ifdef USE_LPUART1
{ SERIAL_PORT_LPUART1, IO_TAG(LPUART1_RX_PIN), IO_TAG(LPUART1_TX_PIN), IO_TAG(INVERTER_PIN_LPUART1) },
{ SERIAL_PORT_LPUART1, IO_TAG(LPUART1_RX_PIN), IO_TAG(LPUART1_TX_PIN), IO_TAG(NONE) },
#endif
#ifdef USE_SOFTSERIAL1
{ SERIAL_PORT_SOFTSERIAL1, IO_TAG(SOFTSERIAL1_RX_PIN), IO_TAG(SOFTSERIAL1_TX_PIN), IO_TAG(NONE) },
#endif
#ifdef USE_SOFTSERIAL2
{ SERIAL_PORT_SOFTSERIAL2, IO_TAG(SOFTSERIAL2_RX_PIN), IO_TAG(SOFTSERIAL2_TX_PIN), IO_TAG(NONE) },
#endif
};
@ -232,38 +86,21 @@ PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONF
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
{
for (size_t index = 0 ; index < ARRAYLEN(serialDefaultPin) ; index++) {
const serialDefaultPin_t *defpin = &serialDefaultPin[index];
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->txIO;
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->inverterIO;
for (const serialDefaultPin_t *defpin = serialDefaultPin; defpin < ARRAYEND(serialDefaultPin); defpin++) {
const int resourceIndex = serialResourceIndex(defpin->ident);
if (resourceIndex >= 0) {
serialPinConfig->ioTagRx[resourceIndex] = defpin->rxIO;
serialPinConfig->ioTagTx[resourceIndex] = defpin->txIO;
#if defined(USE_INVERTER)
// LPUART/SOFTSERIAL do not need/support inverter
if (resourceIndex < (int)ARRAYLEN(serialPinConfig->ioTagInverter)) {
serialPinConfig->ioTagInverter[resourceIndex] = defpin->inverterIO;
}
#endif
}
}
}
#if defined(USE_SOFTSERIAL)
typedef struct softSerialDefaultPin_s {
serialPortIdentifier_e ident;
ioTag_t rxIO, txIO;
} softSerialDefaultPin_t;
static const softSerialDefaultPin_t softSerialDefaultPin[SOFTSERIAL_COUNT] = {
#ifdef USE_SOFTSERIAL
{ SERIAL_PORT_SOFTSERIAL1, IO_TAG(SOFTSERIAL1_RX_PIN), IO_TAG(SOFTSERIAL1_TX_PIN) },
{ SERIAL_PORT_SOFTSERIAL2, IO_TAG(SOFTSERIAL2_RX_PIN), IO_TAG(SOFTSERIAL2_TX_PIN) },
#endif
};
PG_REGISTER_WITH_RESET_FN(softSerialPinConfig_t, softSerialPinConfig, PG_SOFTSERIAL_PIN_CONFIG, 0);
void pgResetFn_softSerialPinConfig(softSerialPinConfig_t *softSerialPinConfig)
{
for (size_t index = 0 ; index < ARRAYLEN(softSerialDefaultPin) ; index++) {
const softSerialDefaultPin_t *defpin = &softSerialDefaultPin[index];
softSerialPinConfig->ioTagRx[SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
softSerialPinConfig->ioTagTx[SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->txIO;
}
}
#endif
#endif
#endif

View file

@ -0,0 +1,40 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/*
#defines used for serial port resource access (pin/dma/inversion)
target/serial_post.h normalizes enabled port definitions (and port counts),
values are just renamed here
*/
// use _MAX value here, resource command needs linear mapping
// (UART8 is always at index RESOURCE_UART_OFFSET + 7, no matter which other ports are enabled)
#define RESOURCE_UART_COUNT SERIAL_UART_MAX
#define RESOURCE_LPUART_COUNT SERIAL_LPUART_MAX
#define RESOURCE_SOFTSERIAL_COUNT SERIAL_SOFTSERIAL_MAX
#define RESOURCE_SERIAL_COUNT (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT + RESOURCE_SOFTSERIAL_COUNT)
// resources are stored in one array, in UART, LPUART, SOFTSERIAL order. Code does assume this ordering,
// do not change it without adapting relevant code.
#define RESOURCE_UART_OFFSET 0
#define RESOURCE_LPUART_OFFSET RESOURCE_UART_COUNT
#define RESOURCE_SOFTSERIAL_OFFSET (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT)

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.

View file

@ -22,12 +22,9 @@
#define SOFTSERIAL_BUFFER_SIZE 256
typedef enum {
SOFTSERIAL1 = 0,
SOFTSERIAL2
} softSerialPortIndex_e;
#include "io/serial.h"
serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options);
serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options);
// serialPort API
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);

View file

@ -38,10 +38,13 @@
#include <common/maths.h>
#include "common/utils.h"
#include "io/serial.h"
#include "drivers/dma.h"
#include "drivers/dma_reqmap.h"
#include "drivers/rcc.h"
#include "drivers/serial.h"
#include "drivers/serial_impl.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
@ -63,13 +66,10 @@
#error Undefined UART_{TX,RX}_BUFFER_ATTRIBUTE for this MCU
#endif
#define UART_BUFFERS(n) \
UART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
UART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s
#define LPUART_BUFFERS(n) \
LPUART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
LPUART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s
#define UART_BUFFERS(n) \
UART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
UART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s \
/**/
#ifdef USE_UART1
UART_BUFFERS(1);
@ -112,22 +112,103 @@ UART_BUFFERS(10);
#endif
#ifdef USE_LPUART1
LPUART_BUFFERS(1);
UART_BUFFERS(Lp1); // TODO - maybe some other naming scheme ?
#endif
#undef UART_BUFFERS
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
// store only devices configured for target (USE_UARTx)
// some entries may be unused, for example because of pin configuration
// uartDeviceIdx_e is direct index into this table
FAST_DATA_ZERO_INIT uartDevice_t uartDevice[UARTDEV_COUNT];
// map serialPortIdentifier_e to uartDeviceIdx_e
uartDeviceIdx_e uartDeviceIdxFromIdentifier(serialPortIdentifier_e identifier)
{
uartPort_t *uartPort = serialUART(device, baudRate, mode, options);
if (!uartPort)
return (serialPort_t *)uartPort;
#ifdef USE_DMA
uartPort->txDMAEmpty = true;
#ifdef USE_LPUART1
if (identifier == SERIAL_PORT_LPUART1) {
return UARTDEV_LP1;
}
#endif
#if 1 // TODO ...
// store +1 in table - unset values default to 0
// table is for UART only to save space (LPUART is handled separately)
#define _R(id, dev) [id] = (dev) + 1
static const uartDeviceIdx_e uartMap[] = {
#ifdef USE_UART1
_R(SERIAL_PORT_USART1, UARTDEV_1),
#endif
#ifdef USE_UART2
_R(SERIAL_PORT_USART2, UARTDEV_2),
#endif
#ifdef USE_UART3
_R(SERIAL_PORT_USART3, UARTDEV_3),
#endif
#ifdef USE_UART4
_R(SERIAL_PORT_UART4, UARTDEV_4),
#endif
#ifdef USE_UART5
_R(SERIAL_PORT_UART5, UARTDEV_5),
#endif
#ifdef USE_UART6
_R(SERIAL_PORT_USART6, UARTDEV_6),
#endif
#ifdef USE_UART7
_R(SERIAL_PORT_USART7, UARTDEV_7),
#endif
#ifdef USE_UART8
_R(SERIAL_PORT_USART8, UARTDEV_8),
#endif
#ifdef USE_UART9
_R(SERIAL_PORT_UART9, UARTDEV_9),
#endif
#ifdef USE_UART10
_R(SERIAL_PORT_USART10, UARTDEV_10),
#endif
};
#undef _R
if (identifier >= 0 && identifier < (int)ARRAYLEN(uartMap)) {
// UART case, but given USE_UARTx may not be defined
return uartMap[identifier] ? uartMap[identifier] - 1 : UARTDEV_INVALID;
}
#else
{
const int idx = identifier - SERIAL_PORT_USART1;
if (idx >= 0 && idx < SERIAL_UART_MAX) {
if (BIT(idx) & SERIAL_UART_MASK) {
// return number of enabled UART ports smaller than idx
return popcount((BIT(idx) - 1) & SERIAL_UART_MASK);
} else {
return UARTDEV_INVALID;
}
}
}
#endif
// neither LPUART nor UART
return UARTDEV_INVALID;
}
uartDevice_t *uartDeviceFromIdentifier(serialPortIdentifier_e identifier)
{
const uartDeviceIdx_e deviceIdx = uartDeviceIdxFromIdentifier(identifier);
return deviceIdx != UARTDEV_INVALID ? &uartDevice[deviceIdx] : NULL;
}
serialPort_t *uartOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uartDevice = uartDeviceFromIdentifier(identifier);
if (!uartDevice) {
return NULL;
}
// fill identifier early, so initialization code can use it
uartDevice->port.port.identifier = identifier;
uartPort_t *uartPort = serialUART(uartDevice, baudRate, mode, options);
if (!uartPort) {
return NULL;
}
// common serial initialisation code should move to serialPort::init()
uartPort->port.rxBufferHead = uartPort->port.rxBufferTail = 0;
uartPort->port.txBufferHead = uartPort->port.txBufferTail = 0;
@ -381,6 +462,7 @@ const struct serialPortVTable uartVTable[] = {
}
};
// TODO - move to serial_uart_hw.c
#ifdef USE_DMA
void uartConfigureDma(uartDevice_t *uartdev)
{
@ -388,11 +470,22 @@ void uartConfigureDma(uartDevice_t *uartdev)
const uartHardware_t *hardware = uartdev->hardware;
#ifdef USE_DMA_SPEC
UARTDevice_e device = hardware->device;
const dmaChannelSpec_t *dmaChannelSpec;
const serialPortIdentifier_e uartPortIdentifier = hardware->identifier;
const uartDeviceIdx_e uartDeviceIdx = uartDeviceIdxFromIdentifier(uartPortIdentifier);
if (uartDeviceIdx == UARTDEV_INVALID) {
return;
}
const int resourceIdx = serialResourceIndex(uartPortIdentifier);
const int ownerIndex = serialOwnerIndex(uartPortIdentifier);
const resourceOwner_e ownerTxRx = serialOwnerTxRx(uartPortIdentifier); // rx is always +1
if (serialUartConfig(device)->txDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, device, serialUartConfig(device)->txDmaopt);
const dmaChannelSpec_t *dmaChannelSpec;
const serialUartConfig_t *cfg = serialUartConfig(resourceIdx);
if (!cfg) {
return;
}
if (cfg->txDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, uartDeviceIdx, cfg->txDmaopt);
if (dmaChannelSpec) {
uartPort->txDMAResource = dmaChannelSpec->ref;
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
@ -403,8 +496,8 @@ void uartConfigureDma(uartDevice_t *uartdev)
}
}
if (serialUartConfig(device)->rxDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, device, serialUartConfig(device)->txDmaopt);
if (cfg->rxDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, uartDeviceIdx, cfg->txDmaopt);
if (dmaChannelSpec) {
uartPort->rxDMAResource = dmaChannelSpec->ref;
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
@ -414,7 +507,7 @@ void uartConfigureDma(uartDevice_t *uartdev)
#endif
}
}
#else
#else /* USE_DMA_SPEC */
// Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
if (hardware->rxDMAResource) {
@ -434,11 +527,11 @@ void uartConfigureDma(uartDevice_t *uartdev)
uartPort->txDMAMuxId = hardware->txDMAMuxId;
#endif
}
#endif
#endif /* USE_DMA_SPEC */
if (uartPort->txDMAResource) {
dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
if (dmaAllocate(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(hardware->device))) {
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
if (dmaAllocate(identifier, ownerTxRx, ownerIndex)) {
dmaEnable(identifier);
#if defined(AT32F4)
dmaMuxEnable(identifier, uartPort->txDMAMuxId);
@ -449,8 +542,8 @@ void uartConfigureDma(uartDevice_t *uartdev)
}
if (uartPort->rxDMAResource) {
dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
if (dmaAllocate(identifier, OWNER_SERIAL_RX, RESOURCE_INDEX(hardware->device))) {
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
if (dmaAllocate(identifier, ownerTxRx + 1, ownerIndex)) {
dmaEnable(identifier);
#if defined(AT32F4)
dmaMuxEnable(identifier, uartPort->rxDMAMuxId);
@ -461,12 +554,13 @@ void uartConfigureDma(uartDevice_t *uartdev)
}
#endif
#define UART_IRQHandler(type, number, dev) \
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
{ \
uartPort_t *uartPort = &(uartDevmap[dev]->port); \
uartIrqHandler(uartPort); \
}
#define UART_IRQHandler(type, number, dev) \
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
{ \
uartPort_t *uartPort = &(uartDevice[(dev)].port); \
uartIrqHandler(uartPort); \
} \
/**/
#ifdef USE_UART1
UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
@ -509,7 +603,7 @@ UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
#endif
#ifdef USE_LPUART1
UART_IRQHandler(LPUART, 1, LPUARTDEV_1) // LPUART1 Rx/Tx IRQ Handler
UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
#endif

View file

@ -21,30 +21,7 @@
#pragma once
#include "drivers/dma.h" // For dmaResource_t
// Since serial ports can be used for any function these buffer sizes should be equal
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
// increase size further.
typedef enum {
UARTDEV_1 = 0,
UARTDEV_2 = 1,
UARTDEV_3 = 2,
UARTDEV_4 = 3,
UARTDEV_5 = 4,
UARTDEV_6 = 5,
UARTDEV_7 = 6,
UARTDEV_8 = 7,
UARTDEV_9 = 8,
UARTDEV_10 = 9,
LPUARTDEV_1 = 10,
UARTDEV_COUNT
} UARTDevice_e;
STATIC_ASSERT(UARTDEV_COUNT == SERIAL_PORT_MAX_INDEX, serial_pinconfig_does_not_match_uartdevs);
#include "io/serial.h" // TODO: maybe move serialPortIdentifier_e into separate header
typedef struct uartPort_s {
serialPort_t port;
@ -84,4 +61,4 @@ typedef struct uartPort_s {
} uartPort_t;
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig);
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options);
serialPort_t *uartOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options);

View file

@ -0,0 +1,210 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Common UART hardware functions
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#if defined(USE_UART) && !defined(SIMULATOR_BUILD)
#include "build/build_config.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
#include "drivers/inverter.h"
#include "drivers/serial.h"
#include "drivers/serial_impl.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
// TODO: split this function into mcu-specific UART files ?
static void enableRxIrq(const uartHardware_t *hardware)
{
#if defined(USE_HAL_DRIVER)
HAL_NVIC_SetPriority(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->irqn);
#elif defined(STM32F4)
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#elif defined(AT32F4)
nvic_irq_enable(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
#elif defined(APM32F4)
DAL_NVIC_SetPriority(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
DAL_NVIC_EnableIRQ(hardware->irqn);
#else
# error "Unhandled MCU type"
#endif
}
uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartPort_t *s = &uartdev->port;
const uartHardware_t *hardware = uartdev->hardware;
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->USARTx = hardware->reg;
#ifdef USE_HAL_DRIVER
s->Handle.Instance = hardware->reg;
#endif
s->checkUsartTxOutput = checkUsartTxOutput;
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
#ifdef USE_DMA
uartConfigureDma(uartdev);
s->txDMAEmpty = true;
#endif
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
const serialPortIdentifier_e identifier = s->port.identifier;
const int ownerIndex = serialOwnerIndex(identifier);
const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
// prepare AF modes
#if UART_TRAIT_AF_PORT
uint8_t rxAf = hardware->af;
uint8_t txAf = hardware->af;
#elif UART_TRAIT_AF_PIN
uint8_t rxAf = uartdev->rx.af;
uint8_t txAf = uartdev->tx.af;
#endif
// Note: F4 did not check txIO before refactoring
if ((options & SERIAL_BIDIR) && txIO) {
// pushPull / openDrain
const bool pushPull = serialOptions_pushPull(options);
// pull direction
const serialPullMode_t pull = serialOptions_pull(options);
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
// Note: APM32F4 is different from STM32F4 here
const ioConfig_t ioCfg = IO_CONFIG(
pushPull ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((const unsigned[]){GPIO_NOPULL, GPIO_PULLDOWN, GPIO_PULLUP})[pull]
);
#elif defined(AT32F4)
const ioConfig_t ioCfg = IO_CONFIG(
GPIO_MODE_MUX,
GPIO_DRIVE_STRENGTH_STRONGER,
pushPull ? GPIO_OUTPUT_PUSH_PULL : GPIO_OUTPUT_OPEN_DRAIN,
((const gpio_pull_type[]){GPIO_PULL_NONE, GPIO_PULL_DOWN, GPIO_PULL_UP})[pull]
);
#elif defined(STM32F4)
// UART inverter is not supproted on F4, but keep it in line with other CPUs
// External inverter in bidir mode would be quite problematic anyway
const ioConfig_t ioCfg = IO_CONFIG(
GPIO_Mode_AF,
GPIO_Low_Speed, // TODO: should use stronger drive
pushPull ? GPIO_OType_PP : GPIO_OType_OD,
((const unsigned[]){GPIO_PuPd_NOPULL, GPIO_PuPd_DOWN, GPIO_PuPd_UP})[pull]
);
#endif
IOInit(txIO, ownerTxRx, ownerIndex);
IOConfigGPIOAF(txIO, ioCfg, txAf);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, ownerTxRx, ownerIndex);
if (options & SERIAL_CHECK_TX) {
#if defined(STM32F7)
// see https://github.com/betaflight/betaflight/pull/13021
// Allow for F7 UART idle preamble to be sent on startup
uartdev->txPinState = TX_PIN_MONITOR;
// Switch TX to UART output whilst UART sends idle preamble
checkUsartTxOutput(s);
#else
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
#endif
} else {
#if defined(STM32F4) || defined(APM32F4)
// TODO: no need for pullup on TX only pin
const ioConfig_t ioCfg = IOCFG_AF_PP_UP;
#else
const ioConfig_t ioCfg = IOCFG_AF_PP;
#endif
IOConfigGPIOAF(txIO, ioCfg, txAf);
}
}
if ((mode & MODE_RX) && rxIO) {
#if defined(STM32F4) || defined(APM32F4)
// no inversion possible on F4, always use pullup
const ioConfig_t ioCfg = IOCFG_AF_PP_UP;
#else
// TODO: pullup/pulldown should be enabled for RX (based on inversion)
const ioConfig_t ioCfg = IOCFG_AF_PP;
#endif
IOInit(rxIO, ownerTxRx + 1, ownerIndex);
IOConfigGPIOAF(rxIO, ioCfg, rxAf);
}
}
if (true
#ifdef USE_DMA
&& !s->rxDMAResource // do not enable IRW if using rxDMA
#endif
) {
enableRxIrq(hardware);
}
return s;
}
// called from platform-specific uartReconfigure
void uartConfigureExternalPinInversion(uartPort_t *uartPort)
{
#if !defined(USE_INVERTER)
UNUSED(uartPort);
#else
const bool inverted = uartPort->port.options & SERIAL_INVERTED;
enableInverter(uartPort->port.identifier, inverted);
#endif
}
#endif /* USE_UART */

View file

@ -22,8 +22,28 @@
// Configuration constants
// TODO: this comment is obsolete
// Since serial ports can be used for any function these buffer sizes should be equal
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
// increase size further.
// define some common UART features
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F43x)
#define UART_TRAIT_AF_PIN 1 // pin AF mode is configured for each pin individually
#else
#define UART_TRAIT_AF_PORT 1 // all pins on given uart use same AF
#endif
#if !defined(STM32F4) || !defined(APM32F4) // all others support pinswap
#define UART_TRAIT_PINSWAP 1
#endif
#if defined(STM32F4)
#define UARTDEV_COUNT_MAX 6
#define UARTHARDWARE_MAX_PINS 4
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -35,8 +55,9 @@
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
#elif defined(STM32F7)
#define UARTDEV_COUNT_MAX 8
#define UARTHARDWARE_MAX_PINS 4
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -48,8 +69,9 @@
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
#elif defined(STM32H7)
#define UARTDEV_COUNT_MAX 11 // UARTs 1 to 10 + LPUART1
#define UARTHARDWARE_MAX_PINS 5
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -61,8 +83,9 @@
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
#elif defined(STM32G4)
#define UARTDEV_COUNT_MAX 11 // UARTs 1 to 5 + LPUART1 (index 10)
#define UARTHARDWARE_MAX_PINS 3
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -74,8 +97,9 @@
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
#elif defined(AT32F4)
#define UARTDEV_COUNT_MAX 8 // UARTs 1 to 5 + LPUART1 (index 9)
#define UARTHARDWARE_MAX_PINS 5
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -88,7 +112,7 @@
#endif
#endif
#elif defined(APM32F4)
#define UARTDEV_COUNT_MAX 6
#define UARTHARDWARE_MAX_PINS 4
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256
@ -100,89 +124,59 @@
#define UART_TX_BUFFER_SIZE 256
#endif
#endif
#else
#error unknown MCU family
#endif
// Count number of configured UARTs
// compressed index of UART/LPUART. Direct index into uartDevice[]
typedef enum {
UARTDEV_INVALID = -1,
#ifdef USE_UART1
#define UARTDEV_COUNT_1 1
#else
#define UARTDEV_COUNT_1 0
UARTDEV_1,
#endif
#ifdef USE_UART2
#define UARTDEV_COUNT_2 1
#else
#define UARTDEV_COUNT_2 0
UARTDEV_2,
#endif
#ifdef USE_UART3
#define UARTDEV_COUNT_3 1
#else
#define UARTDEV_COUNT_3 0
UARTDEV_3,
#endif
#ifdef USE_UART4
#define UARTDEV_COUNT_4 1
#else
#define UARTDEV_COUNT_4 0
UARTDEV_4,
#endif
#ifdef USE_UART5
#define UARTDEV_COUNT_5 1
#else
#define UARTDEV_COUNT_5 0
UARTDEV_5,
#endif
#ifdef USE_UART6
#define UARTDEV_COUNT_6 1
#else
#define UARTDEV_COUNT_6 0
UARTDEV_6,
#endif
#ifdef USE_UART7
#define UARTDEV_COUNT_7 1
#else
#define UARTDEV_COUNT_7 0
UARTDEV_7,
#endif
#ifdef USE_UART8
#define UARTDEV_COUNT_8 1
#else
#define UARTDEV_COUNT_8 0
UARTDEV_8,
#endif
#ifdef USE_UART9
#define UARTDEV_COUNT_9 1
#else
#define UARTDEV_COUNT_9 0
UARTDEV_9,
#endif
#ifdef USE_UART10
#define UARTDEV_COUNT_10 1
#else
#define UARTDEV_COUNT_10 0
UARTDEV_10,
#endif
#ifdef USE_LPUART1
#define LPUARTDEV_COUNT_1 1
#else
#define LPUARTDEV_COUNT_1 0
UARTDEV_LP1,
#endif
#define UARTDEV_COUNT (UARTDEV_COUNT_1 + UARTDEV_COUNT_2 + UARTDEV_COUNT_3 + UARTDEV_COUNT_4 + UARTDEV_COUNT_5 + UARTDEV_COUNT_6 + UARTDEV_COUNT_7 + UARTDEV_COUNT_8 + UARTDEV_COUNT_9 + UARTDEV_COUNT_10 + LPUARTDEV_COUNT_1)
UARTDEV_COUNT
} uartDeviceIdx_e;
typedef struct uartPinDef_s {
ioTag_t pin;
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F43x) || defined(APM32F4)
#if UART_TRAIT_AF_PIN
uint8_t af;
#endif
} uartPinDef_t;
typedef struct uartHardware_s {
UARTDevice_e device; // XXX Not required for full allocation
serialPortIdentifier_e identifier;
USART_TypeDef* reg;
#ifdef USE_DMA
@ -190,7 +184,7 @@ typedef struct uartHardware_s {
dmaResource_t *rxDMAResource;
// For H7 and G4 , {tx|rx}DMAChannel are DMAMUX input index for peripherals (DMA_REQUEST_xxx); H7:RM0433 Table 110, G4:RM0440 Table 80.
// For F4 and F7, these are 32-bit channel identifiers (DMA_CHANNEL_x)
// For at32f435/7 DmaChannel is the dmamux ,need to call dmamuxenable using dmamuxid
// For at32f435/7 DmaChannel is the dmamux, need to call dmamuxenable using dmamuxid
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
uint32_t txDMAChannel;
uint32_t rxDMAChannel;
@ -206,16 +200,12 @@ typedef struct uartHardware_s {
rccPeriphTag_t rcc;
#if !defined(STM32F7)
#if UART_TRAIT_AF_PORT
uint8_t af;
#endif
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
uint8_t txIrq;
uint8_t rxIrq;
#else
uint8_t irqn;
#endif
uint8_t irqn; // uart IRQ. One shared IRQ per uart
uint8_t txPriority;
uint8_t rxPriority;
@ -225,7 +215,7 @@ typedef struct uartHardware_s {
uint16_t rxBufferSize;
} uartHardware_t;
extern const uartHardware_t uartHardware[];
extern const uartHardware_t uartHardware[UARTDEV_COUNT];
// uartDevice_t is an actual device instance.
// XXX Instances are allocated for uarts defined by USE_UARTx atm.
@ -236,6 +226,7 @@ typedef enum {
TX_PIN_IGNORE
} txPinState_t;
// TODO: merge uartPort_t and uartDevice_t
typedef struct uartDevice_s {
uartPort_t port;
const uartHardware_t *hardware;
@ -243,19 +234,24 @@ typedef struct uartDevice_s {
uartPinDef_t tx;
volatile uint8_t *rxBuffer;
volatile uint8_t *txBuffer;
#if !defined(STM32F4) || !defined(APM32F4) // Don't support pin swap.
#if UART_TRAIT_PINSWAP
bool pinSwap;
#endif
txPinState_t txPinState;
} uartDevice_t;
extern uartDevice_t *uartDevmap[];
extern uartDevice_t uartDevice[UARTDEV_COUNT]; // indexed by uartDeviceIdx_e;
uartDeviceIdx_e uartDeviceIdxFromIdentifier(serialPortIdentifier_e identifier);
uartDevice_t* uartDeviceFromIdentifier(serialPortIdentifier_e identifier);
extern const struct serialPortVTable uartVTable[];
void uartTryStartTxDMA(uartPort_t *s);
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options);
uartPort_t *serialUART(uartDevice_t *uart, uint32_t baudRate, portMode_e mode, portOptions_e options);
void uartConfigureExternalPinInversion(uartPort_t *uartPort);
void uartIrqHandler(uartPort_t *s);
@ -284,15 +280,10 @@ void uartTxMonitor(uartPort_t *s);
#define UART_BUFFER(type, n, rxtx) type volatile uint8_t uart ## n ## rxtx ## xBuffer[UART_ ## rxtx ## X_BUFFER_SIZE]
#define UART_BUFFERS_EXTERN(n) \
UART_BUFFER(extern, n, R); \
UART_BUFFER(extern, n, T); struct dummy_s
#define LPUART_BUFFER(type, n, rxtx) type volatile uint8_t lpuart ## n ## rxtx ## xBuffer[UART_ ## rxtx ## X_BUFFER_SIZE]
#define LPUART_BUFFERS_EXTERN(n) \
LPUART_BUFFER(extern, n, R); \
LPUART_BUFFER(extern, n, T); struct dummy_s
#define UART_BUFFERS_EXTERN(n) \
UART_BUFFER(extern, n, R); \
UART_BUFFER(extern, n, T); struct dummy_s \
/**/
#ifdef USE_UART1
UART_BUFFERS_EXTERN(1);
@ -335,7 +326,7 @@ UART_BUFFERS_EXTERN(10);
#endif
#ifdef USE_LPUART1
LPUART_BUFFERS_EXTERN(1);
UART_BUFFERS_EXTERN(Lp1);
#endif
#undef UART_BUFFERS_EXTERN

View file

@ -41,48 +41,47 @@
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
static FAST_DATA_ZERO_INIT uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
FAST_DATA_ZERO_INIT uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
{
uartDevice_t *uartdev = uartDevice;
for (size_t hindex = 0; hindex < UARTDEV_COUNT; hindex++) {
const uartHardware_t *hardware = &uartHardware[hindex];
const UARTDevice_e device = hardware->device;
#if !defined(STM32F4) || !defined(APM32F4) // Don't support pin swap.
uartdev->pinSwap = false;
for (const uartHardware_t* hardware = uartHardware; hardware < ARRAYEND(uartHardware); hardware++) {
const serialPortIdentifier_e identifier = hardware->identifier;
uartDevice_t* uartdev = uartDeviceFromIdentifier(identifier);
const int resourceIndex = serialResourceIndex(identifier);
if (uartdev == NULL || resourceIndex < 0) {
// malformed uartHardware
continue;
}
const ioTag_t cfgRx = pSerialPinConfig->ioTagRx[resourceIndex];
const ioTag_t cfgTx = pSerialPinConfig->ioTagTx[resourceIndex];
#if UART_TRAIT_PINSWAP
bool swap = false;
#endif
for (int pindex = 0 ; pindex < UARTHARDWARE_MAX_PINS ; pindex++) {
if (pSerialPinConfig->ioTagRx[device] && (pSerialPinConfig->ioTagRx[device] == hardware->rxPins[pindex].pin)) {
for (unsigned pindex = 0 ; pindex < UARTHARDWARE_MAX_PINS ; pindex++) {
if (cfgRx && cfgRx == hardware->rxPins[pindex].pin) {
uartdev->rx = hardware->rxPins[pindex];
}
if (pSerialPinConfig->ioTagTx[device] && (pSerialPinConfig->ioTagTx[device] == hardware->txPins[pindex].pin)) {
if (cfgTx && cfgTx == hardware->txPins[pindex].pin) {
uartdev->tx = hardware->txPins[pindex];
}
#if !defined(STM32F4) || !defined(APM32F4)
#if UART_TRAIT_PINSWAP
// Check for swapped pins
if (pSerialPinConfig->ioTagTx[device] && (pSerialPinConfig->ioTagTx[device] == hardware->rxPins[pindex].pin)) {
if (cfgTx && cfgTx == hardware->rxPins[pindex].pin) {
uartdev->tx = hardware->rxPins[pindex];
uartdev->pinSwap = true;
swap = true;
}
if (pSerialPinConfig->ioTagRx[device] && (pSerialPinConfig->ioTagRx[device] == hardware->txPins[pindex].pin)) {
if (cfgRx && cfgRx == hardware->txPins[pindex].pin) {
uartdev->rx = hardware->txPins[pindex];
uartdev->pinSwap = true;
swap = true;
}
#endif
}
if (uartdev->rx.pin || uartdev->tx.pin) {
if (uartdev->rx.pin || uartdev->tx.pin ) {
uartdev->hardware = hardware;
uartDevmap[device] = uartdev++;
#if UART_TRAIT_PINSWAP
uartdev->pinSwap = swap;
#endif
}
}
}

View file

@ -260,7 +260,7 @@ static void sdCardAndFSInit(void)
void init(void)
{
#ifdef SERIAL_PORT_COUNT
#if SERIAL_PORT_COUNT > 0
printfSerialInit();
#endif
@ -519,17 +519,21 @@ void init(void)
#endif
#if defined(AVOID_UART1_FOR_PWM_PPM)
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART1
#elif defined(AVOID_UART2_FOR_PWM_PPM)
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART2
#elif defined(AVOID_UART3_FOR_PWM_PPM)
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
#else
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART3
#endif
{
serialPortIdentifier_e serialPortToAvoid = SERIAL_PORT_NONE;
#if defined(SERIALPORT_TO_AVOID)
if (featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
serialPortToAvoid = SERIALPORT_TO_AVOID;
}
#endif
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), serialPortToAvoid);
}
mixerInit(mixerConfig()->mixerMode);

View file

@ -435,8 +435,8 @@ void gpsInit(void)
mode &= ~MODE_TX;
}
#endif
if ((gpsPortConfig->identifier >= SERIAL_PORT_USART1) && (gpsPortConfig->identifier <= SERIAL_PORT_USART_MAX)){
if (serialType(gpsPortConfig->identifier) == SERIALTYPE_UART
|| serialType(gpsPortConfig->identifier) == SERIALTYPE_LPUART){
options |= SERIAL_CHECK_TX;
}

View file

@ -100,8 +100,10 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#ifdef USE_UART10
SERIAL_PORT_USART10,
#endif
#ifdef USE_SOFTSERIAL
#ifdef USE_SOFTSERIAL1
SERIAL_PORT_SOFTSERIAL1,
#endif
#ifdef USE_SOFTSERIAL2
SERIAL_PORT_SOFTSERIAL2,
#endif
#ifdef USE_LPUART1
@ -109,24 +111,77 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#endif
};
const char* serialPortNames[SERIAL_PORT_COUNT] = {
#ifdef USE_VCP
"VCP",
#endif
#ifdef USE_UART1
"UART1",
#endif
#ifdef USE_UART2
"UART2",
#endif
#ifdef USE_UART3
"UART3",
#endif
#ifdef USE_UART4
"UART4",
#endif
#ifdef USE_UART5
"UART5",
#endif
#ifdef USE_UART6
"UART6",
#endif
#ifdef USE_UART7
"UART7",
#endif
#ifdef USE_UART8
"UART8",
#endif
#ifdef USE_UART9
"UART9",
#endif
#ifdef USE_UART10
"UART10",
#endif
#ifdef USE_SOFTSERIAL1
"SOFT1",
#endif
#ifdef USE_SOFTSERIAL2
"SOFT2",
#endif
#ifdef USE_LPUART1
"LPUART1",
#endif
};
static uint8_t serialPortCount;
const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
#define BAUD_RATE_COUNT ARRAYLEN(baudRates)
serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
static serialPortConfig_t* findInPortConfigs_identifier(const serialPortConfig_t cfgs[], size_t count, serialPortIdentifier_e identifier)
{
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
if (candidate->identifier == identifier) {
return candidate;
for (unsigned i = 0; i < count; i++) {
if (cfgs[i].identifier == identifier) {
// drop const on return - wrapper function will add it back if necessary
return (serialPortConfig_t*)&cfgs[i];
}
}
return NULL;
}
serialPortConfig_t* serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
{
return findInPortConfigs_identifier(serialConfigMutable()->portConfigs, ARRAYLEN(serialConfigMutable()->portConfigs), identifier);
}
const serialPortConfig_t* serialFindPortConfiguration(serialPortIdentifier_e identifier)
{
return findInPortConfigs_identifier(serialConfigMutable()->portConfigs, ARRAYLEN(serialConfig()->portConfigs), identifier);
}
PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
void pgResetFn_serialConfig(serialConfig_t *serialConfig)
@ -134,11 +189,12 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
memset(serialConfig, 0, sizeof(serialConfig_t));
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_57600;
serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
serialConfig->portConfigs[i].blackbox_baudrateIndex = BAUD_115200;
serialPortConfig_t* pCfg = &serialConfig->portConfigs[i];
pCfg->identifier = serialPortIdentifiers[i];
pCfg->msp_baudrateIndex = BAUD_115200;
pCfg->gps_baudrateIndex = BAUD_57600;
pCfg->telemetry_baudrateIndex = BAUD_AUTO;
pCfg->blackbox_baudrateIndex = BAUD_115200;
}
serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
@ -221,9 +277,7 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
baudRate_e lookupBaudRateIndex(uint32_t baudRate)
{
uint8_t index;
for (index = 0; index < BAUD_RATE_COUNT; index++) {
for (unsigned index = 0; index < ARRAYLEN(baudRates); index++) {
if (baudRates[index] == baudRate) {
return index;
}
@ -233,7 +287,7 @@ baudRate_e lookupBaudRateIndex(uint32_t baudRate)
int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
{
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
for (unsigned index = 0; index < ARRAYLEN(serialPortIdentifiers); index++) {
if (serialPortIdentifiers[index] == identifier) {
return index;
}
@ -241,13 +295,35 @@ int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
return -1;
}
// find serial port by name.
// when cmp is NULL, case-insensitive compare is used
// cmp is strcmp-like function
serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(const char *portName, const char *candidate))
{
if (!cmp) { // use strcasecmp by default
cmp = strcasecmp;
}
for (unsigned i = 0; i < ARRAYLEN(serialPortNames); i++) {
if (cmp(portName, serialPortNames[i]) == 0) {
return serialPortIdentifiers[i]; // 1:1 map between names and identifiers
}
}
return SERIAL_PORT_NONE;
}
const char* serialName(serialPortIdentifier_e identifier, const char* notFound)
{
const int idx = findSerialPortIndexByIdentifier(identifier);
return idx >= 0 ? serialPortNames[idx] : notFound;
}
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
{
uint8_t index;
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortUsage_t *candidate = &serialPortUsageList[index];
if (candidate->identifier == identifier) {
return candidate;
for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) {
if (usage->identifier == identifier) {
return usage;
}
}
return NULL;
@ -255,11 +331,9 @@ serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identi
serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort)
{
uint8_t index;
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortUsage_t *candidate = &serialPortUsageList[index];
if (candidate->serialPort == serialPort) {
return candidate;
for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) {
if (usage->serialPort == serialPort) {
return usage;
}
}
return NULL;
@ -280,7 +354,7 @@ const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
{
while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
while (findSerialPortConfigState.lastIndex < ARRAYLEN(serialConfig()->portConfigs)) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
if (candidate->functionMask & function) {
@ -305,7 +379,7 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionM
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
{
for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
for (unsigned i = 0; i < ARRAYLEN(serialConfig()->portConfigs); i++) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
@ -338,12 +412,11 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
*/
uint8_t mspPortCount = 0;
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
for (unsigned index = 0; index < ARRAYLEN(serialConfigToCheck->portConfigs); index++) {
const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
#ifdef USE_SOFTSERIAL
if ((portConfig->identifier == SERIAL_PORT_SOFTSERIAL1) ||
(portConfig->identifier == SERIAL_PORT_SOFTSERIAL2)) {
if (serialType(portConfig->identifier) == SERIALTYPE_SOFTSERIAL) {
// Ensure MSP or serial RX is not enabled on soft serial ports
serialConfigToCheck->portConfigs[index].functionMask &= ~(FUNCTION_MSP | FUNCTION_RX_SERIAL);
// Ensure that the baud rate on soft serial ports is limited to 19200
@ -357,12 +430,14 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
if (portConfig->functionMask & FUNCTION_MSP) {
mspPortCount++;
} else if (portConfig->identifier == SERIAL_PORT_USB_VCP) {
}
if (portConfig->identifier == SERIAL_PORT_USB_VCP
&& (portConfig->functionMask & FUNCTION_MSP) == 0) {
// Require MSP to be enabled for the VCP port
return false;
}
uint8_t bitCount = BITCOUNT(portConfig->functionMask);
uint8_t bitCount = popcount(portConfig->functionMask);
#ifdef USE_VTX_MSP
if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
@ -395,17 +470,6 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
return true;
}
const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
{
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index];
if (candidate->identifier == identifier) {
return candidate;
}
}
return NULL;
}
bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
{
const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
@ -421,7 +485,7 @@ serialPort_t *openSerialPort(
portMode_e mode,
portOptions_e options)
{
#if !(defined(USE_UART) || defined(USE_SOFTSERIAL))
#if !(defined(USE_UART) || defined(USE_SOFTSERIAL) || defined(USE_LPUART))
UNUSED(rxCallback);
UNUSED(rxCallbackData);
UNUSED(baudRate);
@ -437,71 +501,34 @@ serialPort_t *openSerialPort(
serialPort_t *serialPort = NULL;
#if defined(USE_SOFTSERIAL) && !defined(USE_OVERRIDE_SOFTSERIAL_BAUDRATE)
if (((identifier == SERIAL_PORT_SOFTSERIAL1) || (identifier == SERIAL_PORT_SOFTSERIAL2)) && (baudRate > 19200)) {
// Don't continue if baud rate requested is higher then the limit set on soft serial ports
return NULL;
}
switch (serialType(identifier)) {
#if defined(USE_VCP)
case SERIALTYPE_USB_VCP:
serialPort = usbVcpOpen();
break;
#endif
switch (identifier) {
#ifdef USE_VCP
case SERIAL_PORT_USB_VCP:
serialPort = usbVcpOpen();
break;
#endif
#if defined(USE_UART)
#ifdef USE_UART1
case SERIAL_PORT_USART1:
#endif
#ifdef USE_UART2
case SERIAL_PORT_USART2:
#endif
#ifdef USE_UART3
case SERIAL_PORT_USART3:
#endif
#ifdef USE_UART4
case SERIAL_PORT_UART4:
#endif
#ifdef USE_UART5
case SERIAL_PORT_UART5:
#endif
#ifdef USE_UART6
case SERIAL_PORT_USART6:
#endif
#ifdef USE_UART7
case SERIAL_PORT_USART7:
#endif
#ifdef USE_UART8
case SERIAL_PORT_USART8:
#endif
#ifdef USE_UART9
case SERIAL_PORT_UART9:
#endif
#ifdef USE_UART10
case SERIAL_PORT_USART10:
#endif
#ifdef USE_LPUART1
case SERIAL_PORT_LPUART1:
#endif
case SERIALTYPE_UART:
case SERIALTYPE_LPUART:
#if defined(SIMULATOR_BUILD)
// emulate serial ports over TCP
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
// emulate serial ports over TCP
serialPort = serTcpOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
#else
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
serialPort = uartOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
#endif
break;
#endif
break;
#ifdef USE_SOFTSERIAL
case SERIAL_PORT_SOFTSERIAL1:
serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
break;
case SERIAL_PORT_SOFTSERIAL2:
serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
break;
#endif
case SERIALTYPE_SOFTSERIAL:
# if !defined(USE_OVERRIDE_SOFTSERIAL_BAUDRATE)
if (baudRate > 19200) {
// Don't continue if baud rate requested is higher then the limit set on soft serial ports
return NULL;
}
# endif // !USE_OVERRIDE_SOFTSERIAL_BAUDRATE
serialPort = softSerialOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
break;
#endif // USE_SOFTSERIAL
default:
break;
}
@ -510,7 +537,7 @@ serialPort_t *openSerialPort(
return NULL;
}
serialPort->identifier = identifier;
serialPort->identifier = identifier; // Some versions of *Open() set this member sooner
serialPortUsage->function = function;
serialPortUsage->serialPort = serialPort;
@ -545,50 +572,43 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
if (serialPortToDisable != SERIAL_PORT_NONE) {
if (serialPortUsageList[index].identifier == serialPortToDisable) {
if (serialPortToDisable != SERIAL_PORT_NONE
&& serialPortUsageList[index].identifier == serialPortToDisable) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
continue; // this index is deleted
}
#if !defined(SIMULATOR_BUILD)
else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART10
#ifdef USE_LPUART1
|| serialPortUsageList[index].identifier == SERIAL_PORT_LPUART1
#endif
) {
int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
}
#endif
#ifdef USE_SOFTSERIAL
else if (((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1) &&
(!softserialEnabled || !(softSerialPinConfig()->ioTagRx[SOFTSERIAL1] || softSerialPinConfig()->ioTagTx[SOFTSERIAL1]))) ||
((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2) &&
(!softserialEnabled || !(softSerialPinConfig()->ioTagRx[SOFTSERIAL2] || softSerialPinConfig()->ioTagTx[SOFTSERIAL2]))))
#else
else if (
(serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1) ||
(serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2)
)
#endif
{
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
#if !defined(SIMULATOR_BUILD) // no serialPinConfig on SITL
const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier);
if (resourceIndex >= 0 // resource exists
&& !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
continue;
}
#endif
}
if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL) {
if (true
#ifdef USE_SOFTSERIAL
&& !softserialEnabled
#endif
) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
continue;
}
}
}
}
void serialRemovePort(serialPortIdentifier_e identifier)
{
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
if (serialPortUsageList[index].identifier == identifier) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
serialPortUsage_t* usage;
while ((usage = findSerialPortUsageByIdentifier(identifier)) != NULL) {
usage->identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
}
@ -599,12 +619,7 @@ uint8_t serialGetAvailablePortCount(void)
bool serialIsPortAvailable(serialPortIdentifier_e identifier)
{
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
if (serialPortUsageList[index].identifier == identifier) {
return true;
}
}
return false;
return findSerialPortUsageByIdentifier(identifier) != NULL;
}
void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)

View file

@ -83,40 +83,46 @@ typedef enum {
SERIAL_PORT_ALL = -2,
SERIAL_PORT_NONE = -1,
SERIAL_PORT_USART1 = 0,
SERIAL_PORT_UART1 = SERIAL_PORT_USART1,
SERIAL_PORT_USART2,
SERIAL_PORT_UART2 = SERIAL_PORT_USART2,
SERIAL_PORT_USART3,
SERIAL_PORT_UART3 = SERIAL_PORT_USART3,
SERIAL_PORT_UART4,
SERIAL_PORT_UART5,
SERIAL_PORT_USART6,
SERIAL_PORT_UART6 = SERIAL_PORT_USART6,
SERIAL_PORT_USART7,
SERIAL_PORT_UART7 = SERIAL_PORT_USART7,
SERIAL_PORT_USART8,
SERIAL_PORT_UART8 = SERIAL_PORT_USART8,
SERIAL_PORT_UART9,
SERIAL_PORT_USART10,
SERIAL_PORT_UART10 = SERIAL_PORT_USART10,
SERIAL_PORT_USART_MAX = SERIAL_PORT_USART10,
SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2,
SERIAL_PORT_LPUART1 = 40,
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_LPUART1,
} serialPortIdentifier_e;
// use value from target serial port normalization
#define SERIAL_PORT_COUNT (SERIAL_UART_COUNT + SERIAL_LPUART_COUNT + SERIAL_SOFTSERIAL_COUNT + SERIAL_VCP_COUNT)
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
#define SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(x) ((x) - SERIAL_PORT_SOFTSERIAL1)
typedef enum {
SERIALTYPE_INVALID = -1,
SERIALTYPE_USB_VCP = 0,
SERIALTYPE_UART,
SERIALTYPE_LPUART,
SERIALTYPE_SOFTSERIAL,
SERIALTYPE_COUNT
} serialType_e;
#if defined(USE_LPUART1)
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) \
(((x) <= SERIAL_PORT_USART_MAX) ? ((x) - SERIAL_PORT_USART1) : ((x) - SERIAL_PORT_LPUART1) + LPUARTDEV_1)
#define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) \
(((x) <= SERIAL_PORT_USART_MAX) ? ((x) - SERIAL_PORT_USART1 + UARTDEV_1) : ((x) - SERIAL_PORT_LPUART1) + LPUARTDEV_1)
#else
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) ((x) - SERIAL_PORT_USART1)
#define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) ((x) - SERIAL_PORT_USART1 + UARTDEV_1)
#endif
//
// runtime
//
@ -170,6 +176,9 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionM
void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier);
serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(const char *portName, const char *candidate));
const char* serialName(serialPortIdentifier_e identifier, const char* notFound);
//
// runtime
//
@ -188,6 +197,10 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
baudRate_e lookupBaudRateIndex(uint32_t baudRate);
serialType_e serialType(serialPortIdentifier_e identifier);
// resource index of given identifier, or -1 if not available
int serialResourceIndex(serialPortIdentifier_e identifier);
//
// msp/cli/bootloader

View file

@ -0,0 +1,128 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <limits.h>
#include "platform.h"
#include "io/serial.h"
// convert identifier into port type
serialType_e serialType(serialPortIdentifier_e identifier)
{
#ifdef USE_VCP
if (identifier == SERIAL_PORT_USB_VCP) {
return SERIALTYPE_USB_VCP;
}
#endif
#ifdef USE_UART
if (identifier >= SERIAL_PORT_USART1 && identifier < SERIAL_PORT_USART1 + SERIAL_UART_MAX) {
const unsigned idx = identifier - SERIAL_PORT_USART1;
if (BIT(idx) & SERIAL_UART_MASK) {
return SERIALTYPE_UART;
} else {
// no other type in this range
return SERIALTYPE_INVALID;
}
}
#endif
#ifdef USE_LPUART
if (identifier >= SERIAL_PORT_LPUART1 && identifier < SERIAL_PORT_LPUART1 + SERIAL_LPUART_MAX) {
const unsigned idx = identifier - SERIAL_PORT_LPUART1;
if (BIT(idx) & SERIAL_LPUART_MASK) {
return SERIALTYPE_LPUART;
} else {
// no other type in this range
return SERIALTYPE_INVALID;
}
}
#endif
#ifdef USE_SOFTSERIAL
if (identifier >= SERIAL_PORT_SOFTSERIAL1 && identifier < SERIAL_PORT_SOFTSERIAL1 + SERIAL_SOFTSERIAL_MAX) {
// sotserials always start from 1, without holes
return SERIALTYPE_SOFTSERIAL;
}
#endif
return SERIALTYPE_INVALID;
}
static const struct SerialTypeInfo {
resourceOwner_e owner;
serialPortIdentifier_e firstId;
int8_t resourceOffset;
} serialTypeMap[] = {
[SERIALTYPE_USB_VCP] = { OWNER_FREE /* no owner*/, SERIAL_PORT_USB_VCP, -1 },
[SERIALTYPE_UART] = { OWNER_SERIAL_TX, SERIAL_PORT_USART1, RESOURCE_UART_OFFSET },
[SERIALTYPE_LPUART] = { OWNER_LPUART_TX, SERIAL_PORT_LPUART1, RESOURCE_LPUART_OFFSET },
[SERIALTYPE_SOFTSERIAL] = { OWNER_SOFTSERIAL_TX, SERIAL_PORT_SOFTSERIAL1, RESOURCE_SOFTSERIAL_OFFSET },
};
STATIC_ASSERT(ARRAYLEN(serialTypeMap) == SERIALTYPE_COUNT, "type table mismatch");
static const struct SerialTypeInfo* serialTypeInfo(serialPortIdentifier_e identifier)
{
const serialType_e type = serialType(identifier);
if (type == SERIALTYPE_INVALID) {
return NULL;
}
return serialTypeMap + type;
}
// resourceOwner_e for this serial (UART/LPUART/SOFTSERIAL/..)
// Used together with serialOwnerIndex to identify claimed resources
// Tx member is returned, Rx is always Tx + 1
// OWNER_FREE is returned for serials without owner (VCP)
resourceOwner_e serialOwnerTxRx(serialPortIdentifier_e identifier)
{
const struct SerialTypeInfo* inf = serialTypeInfo(identifier);
return inf ? inf->owner : OWNER_FREE;
}
// return index used to claim given resource. Returned value is 1 based, for IOInit and similar
// 0 is returned when given port is not defined or if it is singleton port (USB)
int serialOwnerIndex(serialPortIdentifier_e identifier)
{
const struct SerialTypeInfo* inf = serialTypeInfo(identifier);
if (!inf || inf->owner == OWNER_FREE) {
return 0;
}
return RESOURCE_INDEX(identifier - inf->firstId);
}
// map identifier into index used to store port resources:
// pins(RX,TX), external inversion, port DMA configuration
// order is UART, LPUART, SOFTSERIAL, with each group using index
// coresponding to port name (UART1 -> 0, UART5 -> 4, but LPUART -> 5 if
// there is no UART6 and higher on given target.
// -1 is returned if given port is not defined or is not using resources
// some code uses this ordering for optimizations, be carefull if reordering is necessary
int serialResourceIndex(serialPortIdentifier_e identifier)
{
const struct SerialTypeInfo* inf = serialTypeInfo(identifier);
if (!inf || inf->resourceOffset < 0) {
return -1;
}
return identifier - inf->firstId + inf->resourceOffset;
}

View file

@ -22,7 +22,6 @@
#include "drivers/serial.h"
#define SMARTAUDIO_SERIAL_OPTIONS SERIAL_NOT_INVERTED | SERIAL_BIDIR_NOPULL | SERIAL_STOPBITS_2
#define SMARTAUDIO_DEFAULT_BAUD 4900
#define SMARTAUDIO_MIN_BAUD 4800
#define SMARTAUDIO_MAX_BAUD 4950

View file

@ -39,7 +39,7 @@ typedef struct vtxSettingsConfig_s {
uint16_t freq; // sets freq in MHz if band=0
uint16_t pitModeFreq; // sets out-of-range pitmode frequency
uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e
uint8_t softserialAlt; // pull line low before sending frame even with SOFTSERIAL
uint8_t softserialAlt; // prepend 0xff before sending frame even with SOFTSERIAL
} vtxSettingsConfig_t;
PG_DECLARE(vtxSettingsConfig_t, vtxSettingsConfig);

View file

@ -199,7 +199,7 @@ static void vtxMspProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
if (isCrsfPortConfig(portConfig)) {
mspCrsfPush(MSP_VTX_CONFIG, frame, sizeof(frame));
} else {
mspSerialPush((serialPortIdentifier_e) portConfig->identifier, MSP_VTX_CONFIG, frame, sizeof(frame), MSP_DIRECTION_REPLY, MSP_V2_NATIVE);
mspSerialPush(portConfig->identifier, MSP_VTX_CONFIG, frame, sizeof(frame), MSP_DIRECTION_REPLY, MSP_V2_NATIVE);
}
packetCounter++;
mspVtxLastTimeUs = currentTimeUs;

View file

@ -497,26 +497,34 @@ static void saReceiveFrame(uint8_t c)
static void saSendFrame(uint8_t *buf, int len)
{
if (!IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
#ifndef AT32F4
switch (smartAudioSerialPort->identifier) {
case SERIAL_PORT_SOFTSERIAL1:
case SERIAL_PORT_SOFTSERIAL2:
if (vtxSettingsConfig()->softserialAlt) {
serialWrite(smartAudioSerialPort, 0x00); // Generate 1st start byte
}
bool prepend00;
switch (serialType(smartAudioSerialPort->identifier)) {
case SERIALTYPE_SOFTSERIAL:
prepend00 = vtxSettingsConfig()->softserialAlt;
break;
case SERIALTYPE_UART:
case SERIALTYPE_LPUART: // decide HW uarts by MCU type
#ifdef AT32F4
prepend00 = false;
#else
prepend00 = true;
#endif
break;
default:
serialWrite(smartAudioSerialPort, 0x00); // Generate 1st start byte
break;
prepend00 = false;
}
if (prepend00) {
// line is in MARK/BREAK, so only 2 stopbits will be visible (startbit and zeroes are not visible)
// startbit of next byte (0xaa) can be recognized
serialWrite(smartAudioSerialPort, 0x00);
}
#endif //AT32F4
for (int i = 0 ; i < len ; i++) {
serialWrite(smartAudioSerialPort, buf[i]);
}
#ifdef USE_AKK_SMARTAUDIO
#ifdef USE_AKK_SMARTAUDIO
serialWrite(smartAudioSerialPort, 0x00); // AKK/RDQ SmartAudio devices can expect an extra byte due to manufacturing errors.
#endif // USE_AKK_SMARTAUDIO
#endif
saStat.pktsent++;
} else {
@ -705,20 +713,15 @@ bool vtxSmartAudioInit(void)
dprintf(("smartAudioInit: OK\r\n"));
#endif
// Note, for SA, which uses bidirectional mode, would normally require pullups.
// the SA protocol instead requires pulldowns, and therefore uses SERIAL_BIDIR_PP_PD instead of SERIAL_BIDIR_PP
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO);
if (portConfig) {
portOptions_e portOptions = SERIAL_STOPBITS_2 | SERIAL_BIDIR | SERIAL_BIDIR_PP_PD | SERIAL_BIDIR_NOPULL;
#ifdef USE_SMARTAUDIO_NOPULLDOWN
// softserial hack (#13797)
if (smartAudioSerialPort->identifier == SERIAL_PORT_SOFTSERIAL1 || smartAudioSerialPort->identifier == SERIAL_PORT_SOFTSERIAL2) {
portOptions &= ~SERIAL_BIDIR_PP_PD;
portOptions |= SERIAL_BIDIR_PP;
}
#endif
smartAudioSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_SMARTAUDIO, NULL, NULL, 4800, MODE_RXTX, portOptions);
if (!portConfig) {
return false;
}
// Note, for SA, which uses bidirectional mode, would normally require pullups.
// the SA protocol usually requires pulldowns, and therefore uses SERIAL_PULL_SMARTAUDIO together with SERIAL_BIDIR_PP
// serial driver handles different pullup/pulldown/nopull quirks when SERIAL_PULL_SMARTAUDIO is used
const portOptions_e portOptions = SERIAL_NOT_INVERTED | SERIAL_STOPBITS_2 | SERIAL_BIDIR | SERIAL_BIDIR_PP | SERIAL_PULL_SMARTAUDIO;
smartAudioSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_SMARTAUDIO, NULL, NULL, 4800, MODE_RXTX, portOptions);
if (!smartAudioSerialPort) {
return false;

View file

@ -654,9 +654,9 @@ bool vtxTrampInit(void)
if (portConfig) {
portOptions_e portOptions = 0;
#if defined(USE_VTX_COMMON)
portOptions = portOptions | (vtxConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR);
portOptions |= vtxConfig()->halfDuplex ? SERIAL_BIDIR : 0;
#else
portOptions = SERIAL_BIDIR;
portOptions |= SERIAL_BIDIR;
#endif
trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, NULL, 9600, MODE_RXTX, portOptions);

View file

@ -57,7 +57,7 @@ void mspSerialAllocatePorts(void)
{
uint8_t portIndex = 0;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
while (portConfig && portIndex < ARRAYLEN(mspPorts)) {
mspPort_t *mspPort = &mspPorts[portIndex];
if (mspPort->port) {
@ -69,7 +69,8 @@ void mspSerialAllocatePorts(void)
if (mspConfig()->halfDuplex) {
options |= SERIAL_BIDIR;
} else if ((portConfig->identifier >= SERIAL_PORT_USART1) && (portConfig->identifier <= SERIAL_PORT_USART_MAX)){
} else if (serialType(portConfig->identifier) == SERIALTYPE_UART
|| serialType(portConfig->identifier) == SERIALTYPE_LPUART) {
options |= SERIAL_CHECK_TX;
}
@ -87,7 +88,7 @@ void mspSerialAllocatePorts(void)
void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t *candidateMspPort = &mspPorts[portIndex];
if (candidateMspPort->port == serialPort) {
closeSerialPort(serialPort);
@ -96,11 +97,11 @@ void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
}
}
mspDescriptor_t getMspSerialPortDescriptor(const uint8_t portIdentifier)
mspDescriptor_t getMspSerialPortDescriptor(const serialPortIdentifier_e portIdentifier)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t *candidateMspPort = &mspPorts[portIndex];
if (candidateMspPort->port->identifier == portIdentifier) {
if (candidateMspPort->port && candidateMspPort->port->identifier == portIdentifier) {
return candidateMspPort->descriptor;
}
}
@ -110,7 +111,7 @@ mspDescriptor_t getMspSerialPortDescriptor(const uint8_t portIdentifier)
#if defined(USE_TELEMETRY)
void mspSerialReleaseSharedTelemetryPorts(void)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t *candidateMspPort = &mspPorts[portIndex];
if (candidateMspPort->sharedWithTelemetry) {
closeSerialPort(candidateMspPort->port);
@ -520,7 +521,7 @@ void mspProcessPacket(mspPort_t *mspPort, mspProcessCommandFnPtr mspProcessComma
*/
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
@ -576,7 +577,7 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm
bool mspSerialWaiting(void)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
@ -599,7 +600,7 @@ int mspSerialPush(serialPortIdentifier_e port, uint8_t cmd, uint8_t *data, int d
{
int ret = 0;
for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; ARRAYLEN(mspPorts); portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
// XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
@ -628,7 +629,7 @@ uint32_t mspSerialTxBytesFree(void)
{
uint32_t ret = UINT32_MAX;
for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;

View file

@ -128,6 +128,6 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm
void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialReleaseSharedTelemetryPorts(void);
mspDescriptor_t getMspSerialPortDescriptor(const uint8_t portIdentifier);
mspDescriptor_t getMspSerialPortDescriptor(const serialPortIdentifier_e portIdentifier);
int mspSerialPush(serialPortIdentifier_e port, uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction, mspVersion_e mspVersion);
uint32_t mspSerialTxBytesFree(void);

View file

@ -157,8 +157,8 @@
#define PG_RX_EXPRESSLRS_SPI_CONFIG 555
#define PG_SCHEDULER_CONFIG 556
#define PG_MSP_CONFIG 557
#define PG_SOFTSERIAL_PIN_CONFIG 558
#define PG_BETAFLIGHT_END 558
//#define PG_SOFTSERIAL_PIN_CONFIG 558 // removed, merged into SERIAL_PIN_CONFIG
#define PG_BETAFLIGHT_END 557
// OSD configuration (subject to change)

View file

@ -34,49 +34,50 @@
#include "drivers/io_types.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/dma_reqmap.h"
// TODO(hertz@): UARTDEV_CONFIG_MAX is measured to be exactly 8, which cannot accomodate even all the UARTs below
PG_REGISTER_ARRAY_WITH_RESET_FN(serialUartConfig_t, UARTDEV_CONFIG_MAX, serialUartConfig, PG_SERIAL_UART_CONFIG, 0);
typedef struct uartDmaopt_s {
UARTDevice_e device;
serialPortIdentifier_e identifier;
int8_t txDmaopt;
int8_t rxDmaopt;
} uartDmaopt_t;
static uartDmaopt_t uartDmaopt[] = {
static const uartDmaopt_t uartDmaopt[] = {
#ifdef USE_UART1
{ UARTDEV_1, UART1_TX_DMA_OPT, UART1_RX_DMA_OPT },
{ SERIAL_PORT_USART1, UART1_TX_DMA_OPT, UART1_RX_DMA_OPT },
#endif
#ifdef USE_UART2
{ UARTDEV_2, UART2_TX_DMA_OPT, UART2_RX_DMA_OPT },
{ SERIAL_PORT_USART2, UART2_TX_DMA_OPT, UART2_RX_DMA_OPT },
#endif
#ifdef USE_UART3
{ UARTDEV_3, UART3_TX_DMA_OPT, UART3_RX_DMA_OPT },
{ SERIAL_PORT_USART3, UART3_TX_DMA_OPT, UART3_RX_DMA_OPT },
#endif
#ifdef USE_UART4
{ UARTDEV_4, UART4_TX_DMA_OPT, UART4_RX_DMA_OPT },
{ SERIAL_PORT_UART4, UART4_TX_DMA_OPT, UART4_RX_DMA_OPT },
#endif
#ifdef USE_UART5
{ UARTDEV_5, UART5_TX_DMA_OPT, UART5_RX_DMA_OPT },
{ SERIAL_PORT_UART5, UART5_TX_DMA_OPT, UART5_RX_DMA_OPT },
#endif
#ifdef USE_UART6
{ UARTDEV_6, UART6_TX_DMA_OPT, UART6_RX_DMA_OPT },
#ifdef USE_USART6
{ SERIAL_PORT_UART6, UART6_TX_DMA_OPT, UART6_RX_DMA_OPT },
#endif
#ifdef USE_UART7
{ UARTDEV_7, UART7_TX_DMA_OPT, UART7_RX_DMA_OPT },
#ifdef USE_USART7
{ SERIAL_PORT_UART7, UART7_TX_DMA_OPT, UART7_RX_DMA_OPT },
#endif
#ifdef USE_UART8
{ UARTDEV_8, UART8_TX_DMA_OPT, UART8_RX_DMA_OPT },
#ifdef USE_USART8
{ SERIAL_PORT_UART8, UART8_TX_DMA_OPT, UART8_RX_DMA_OPT },
#endif
#ifdef USE_UART9
{ UARTDEV_9, UART9_TX_DMA_OPT, UART9_RX_DMA_OPT },
{ SERIAL_PORT_UART9, UART9_TX_DMA_OPT, UART9_RX_DMA_OPT },
#endif
#ifdef USE_UART10
{ UARTDEV_10, UART10_TX_DMA_OPT, UART10_RX_DMA_OPT },
{ SERIAL_PORT_UART10, UART10_TX_DMA_OPT, UART10_RX_DMA_OPT },
#endif
#ifdef USE_LPUART1
{ LPUARTDEV_1, DMA_OPT_UNUSED, DMA_OPT_UNUSED },
{ SERIAL_PORT_LPUART1, DMA_OPT_UNUSED, DMA_OPT_UNUSED },
#endif
};
@ -88,9 +89,11 @@ void pgResetFn_serialUartConfig(serialUartConfig_t *config)
}
for (unsigned i = 0; i < ARRAYLEN(uartDmaopt); i++) {
UARTDevice_e device = uartDmaopt[i].device;
config[device].txDmaopt = uartDmaopt[i].txDmaopt;
config[device].rxDmaopt = uartDmaopt[i].rxDmaopt;
const int resourceIndex = serialResourceIndex(uartDmaopt[i].identifier);
if (resourceIndex >= 0 && resourceIndex < UARTDEV_CONFIG_MAX) { // hadle corrupted config gracefuly
config[resourceIndex].txDmaopt = uartDmaopt[i].txDmaopt;
config[resourceIndex].rxDmaopt = uartDmaopt[i].rxDmaopt;
}
}
}
#endif

View file

@ -24,12 +24,9 @@
#include <stdbool.h>
#include "pg/pg.h"
#include "drivers/io_types.h"
#include "drivers/dma_reqmap.h"
#include "drivers/serial_resource.h"
// TODO(hertz@): this alternative got out of sync
#define UARTDEV_CONFIG_MAX 11 // Alternative to UARTDEV_COUNT_MAX, which requires serial_uart_imp.h
#define UARTDEV_CONFIG_MAX (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT)
typedef struct serialUartConfig_s {
int8_t txDmaopt;

View file

@ -231,7 +231,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
NULL,
IBUS_BAUDRATE,
portShared ? MODE_RXTX : MODE_RX,
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0)
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED) | ((rxConfig->halfDuplex || portShared) ? SERIAL_BIDIR : 0)
);
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)

View file

@ -189,13 +189,17 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
bool portShared = false;
#endif
// On SBUS, SERIAL_INVERTED is default
const portOptions_e portOptions = SBUS_PORT_OPTIONS
| (rxConfig->serialrx_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED)
| (rxConfig->halfDuplex ? SERIAL_BIDIR : 0);
serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
FUNCTION_RX_SERIAL,
sbusDataReceive,
&sbusFrameData,
sbusBaudRate,
portShared ? MODE_RXTX : MODE_RX,
SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
portOptions
);
if (rxConfig->rssi_src_frame_errors) {

View file

@ -238,9 +238,9 @@ void spektrumBind(rxConfig_t *rxConfig)
return;
}
int index = SERIAL_PORT_IDENTIFIER_TO_INDEX(portConfig->identifier);
ioTag_t txPin = serialPinConfig()->ioTagTx[index];
ioTag_t rxPin = serialPinConfig()->ioTagRx[index];
const int resourceIndex = serialResourceIndex(portConfig->identifier);
const ioTag_t txPin = serialPinConfig()->ioTagTx[resourceIndex];
const ioTag_t rxPin = serialPinConfig()->ioTagRx[resourceIndex];
// Take care half-duplex case
switch (rxRuntimeState.serialrxProvider) {

View file

@ -386,5 +386,5 @@ void voltageStableUpdate(voltageMeter_t* vm)
// voltage is stable when it was within VOLTAGE_STABLE_MAX_DELTA for 10 update periods
bool voltageIsStable(voltageMeter_t* vm)
{
return __builtin_popcount(vm->voltageStableBits & (BIT(VOLTAGE_STABLE_BITS_TOTAL + 1) - 1)) >= VOLTAGE_STABLE_BITS_THRESHOLD;
return popcount(vm->voltageStableBits & (BIT(VOLTAGE_STABLE_BITS_TOTAL + 1) - 1)) >= VOLTAGE_STABLE_BITS_THRESHOLD;
}

View file

@ -94,16 +94,6 @@
#endif
#endif
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
#define USE_UART
#endif
#ifdef USE_UART
#if defined(INVERTER_PIN_UART1) || defined(INVERTER_PIN_UART2) || defined(INVERTER_PIN_UART3) || defined(INVERTER_PIN_UART4) || defined(INVERTER_PIN_UART5) || defined(INVERTER_PIN_UART6)
#define USE_INVERTER
#endif
#endif
#ifndef DEFAULT_MIXER
#define DEFAULT_MIXER MIXER_QUADX
#endif

View file

@ -85,6 +85,10 @@
In the future we can move to specific drivers being added only - to save flash space.
*/
// normalize serial ports definitions
#include "serial_post.h"
#if defined(USE_MAG) && !defined(USE_VIRTUAL_MAG)
#ifndef USE_MAG_DATA_READY_SIGNAL

View file

@ -0,0 +1,523 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
This file is automatically generated by src/utils/gen-serial.py script from src/utils/templates/serial_post.h jinja2 template.
Do not modify this file directly, your changes will be eventually lost.
See template file for aditional documentation.
To generate this file again, run
> python ./src/utils/gen-serial-j2.py > ./src/main/target/serial_post.h
in Betaflight topmost directory.
This include will provide following defines:
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
All <type><n>_(RX|TX)_PINS are normalized too:
- if port is enabled, both will be defined (possibly as NONE)
- if port is not enable, both will be undefined, possibly with warning
- pass -DWARN_UNUSED_SERIAL_PORT to compiler to check pin defined without corresponding port being enabled.
Generated on 2024-11-04
Configuration used:
{ 'LPUART': {'depends': {'UART'}, 'ids': [1]},
'SOFTSERIAL': { 'force_continuous': True,
'ids': [1, 2],
'use_enables_all': True},
'UART': {'ids': [1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 'inverter': True},
'VCP': {'no_pins': True, 'singleton': True}}
*/
#include "common/utils.h" // BIT, LOG2
/**** UART *****/
#if defined(USE_UART1)
# define SERIAL_UART1_USED 1
#else
# define SERIAL_UART1_USED 0
#endif
#if defined(USE_UART2)
# define SERIAL_UART2_USED 1
#else
# define SERIAL_UART2_USED 0
#endif
#if defined(USE_UART3)
# define SERIAL_UART3_USED 1
#else
# define SERIAL_UART3_USED 0
#endif
#if defined(USE_UART4)
# define SERIAL_UART4_USED 1
#else
# define SERIAL_UART4_USED 0
#endif
#if defined(USE_UART5)
# define SERIAL_UART5_USED 1
#else
# define SERIAL_UART5_USED 0
#endif
#if defined(USE_UART6)
# define SERIAL_UART6_USED 1
#else
# define SERIAL_UART6_USED 0
#endif
#if defined(USE_UART7)
# define SERIAL_UART7_USED 1
#else
# define SERIAL_UART7_USED 0
#endif
#if defined(USE_UART8)
# define SERIAL_UART8_USED 1
#else
# define SERIAL_UART8_USED 0
#endif
#if defined(USE_UART9)
# define SERIAL_UART9_USED 1
#else
# define SERIAL_UART9_USED 0
#endif
#if defined(USE_UART10)
# define SERIAL_UART10_USED 1
#else
# define SERIAL_UART10_USED 0
#endif
#define SERIAL_UART_MASK ((SERIAL_UART1_USED * BIT(1 - 1)) | (SERIAL_UART2_USED * BIT(2 - 1)) | (SERIAL_UART3_USED * BIT(3 - 1)) | (SERIAL_UART4_USED * BIT(4 - 1)) | (SERIAL_UART5_USED * BIT(5 - 1)) | (SERIAL_UART6_USED * BIT(6 - 1)) | (SERIAL_UART7_USED * BIT(7 - 1)) | (SERIAL_UART8_USED * BIT(8 - 1)) | (SERIAL_UART9_USED * BIT(9 - 1)) | (SERIAL_UART10_USED * BIT(10 - 1)))
#define SERIAL_UART_COUNT (SERIAL_UART1_USED + SERIAL_UART2_USED + SERIAL_UART3_USED + SERIAL_UART4_USED + SERIAL_UART5_USED + SERIAL_UART6_USED + SERIAL_UART7_USED + SERIAL_UART8_USED + SERIAL_UART9_USED + SERIAL_UART10_USED)
// 0 if no port is defined
#define SERIAL_UART_MAX (SERIAL_UART_MASK ? LOG2(SERIAL_UART_MASK) + 1 : 0)
// enable USE_INVERTED first, before normalization
#if !defined(USE_INVERTER) && (INVERTER_PIN_UART1 || INVERTER_PIN_UART2 || INVERTER_PIN_UART3 || INVERTER_PIN_UART4 || INVERTER_PIN_UART5 || INVERTER_PIN_UART6 || INVERTER_PIN_UART7 || INVERTER_PIN_UART8 || INVERTER_PIN_UART9 || INVERTER_PIN_UART10)
# define USE_INVERTER
#endif
// Normalize UART TX/RX/INVERTER
#if SERIAL_UART1_USED && !defined(UART1_RX_PIN)
# define UART1_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART1_USED && defined(UART1_RX_PIN)
# warning "UART1_RX_PIN is defined but UART1 is not enabled"
#endif
#if !SERIAL_UART1_USED && defined(UART1_RX_PIN)
# undef UART1_RX_PIN
#endif
#if SERIAL_UART1_USED && !defined(UART1_TX_PIN)
# define UART1_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART1_USED && defined(UART1_TX_PIN)
# warning "UART1_TX_PIN is defined but UART1 is not enabled"
#endif
#if !SERIAL_UART1_USED && defined(UART1_TX_PIN)
# undef UART1_TX_PIN
#endif
#if SERIAL_UART1_USED && !defined(INVERTER_PIN_UART1)
# define INVERTER_PIN_UART1 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART1_USED && defined(INVERTER_PIN_UART1)
# warning "INVERTER_PIN_UART1 is defined but UART1 is not enabled"
#endif
#if !SERIAL_UART1_USED && defined(INVERTER_PIN_UART1)
# undef INVERTER_PIN_UART1
#endif
#if SERIAL_UART2_USED && !defined(UART2_RX_PIN)
# define UART2_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART2_USED && defined(UART2_RX_PIN)
# warning "UART2_RX_PIN is defined but UART2 is not enabled"
#endif
#if !SERIAL_UART2_USED && defined(UART2_RX_PIN)
# undef UART2_RX_PIN
#endif
#if SERIAL_UART2_USED && !defined(UART2_TX_PIN)
# define UART2_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART2_USED && defined(UART2_TX_PIN)
# warning "UART2_TX_PIN is defined but UART2 is not enabled"
#endif
#if !SERIAL_UART2_USED && defined(UART2_TX_PIN)
# undef UART2_TX_PIN
#endif
#if SERIAL_UART2_USED && !defined(INVERTER_PIN_UART2)
# define INVERTER_PIN_UART2 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART2_USED && defined(INVERTER_PIN_UART2)
# warning "INVERTER_PIN_UART2 is defined but UART2 is not enabled"
#endif
#if !SERIAL_UART2_USED && defined(INVERTER_PIN_UART2)
# undef INVERTER_PIN_UART2
#endif
#if SERIAL_UART3_USED && !defined(UART3_RX_PIN)
# define UART3_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART3_USED && defined(UART3_RX_PIN)
# warning "UART3_RX_PIN is defined but UART3 is not enabled"
#endif
#if !SERIAL_UART3_USED && defined(UART3_RX_PIN)
# undef UART3_RX_PIN
#endif
#if SERIAL_UART3_USED && !defined(UART3_TX_PIN)
# define UART3_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART3_USED && defined(UART3_TX_PIN)
# warning "UART3_TX_PIN is defined but UART3 is not enabled"
#endif
#if !SERIAL_UART3_USED && defined(UART3_TX_PIN)
# undef UART3_TX_PIN
#endif
#if SERIAL_UART3_USED && !defined(INVERTER_PIN_UART3)
# define INVERTER_PIN_UART3 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART3_USED && defined(INVERTER_PIN_UART3)
# warning "INVERTER_PIN_UART3 is defined but UART3 is not enabled"
#endif
#if !SERIAL_UART3_USED && defined(INVERTER_PIN_UART3)
# undef INVERTER_PIN_UART3
#endif
#if SERIAL_UART4_USED && !defined(UART4_RX_PIN)
# define UART4_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART4_USED && defined(UART4_RX_PIN)
# warning "UART4_RX_PIN is defined but UART4 is not enabled"
#endif
#if !SERIAL_UART4_USED && defined(UART4_RX_PIN)
# undef UART4_RX_PIN
#endif
#if SERIAL_UART4_USED && !defined(UART4_TX_PIN)
# define UART4_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART4_USED && defined(UART4_TX_PIN)
# warning "UART4_TX_PIN is defined but UART4 is not enabled"
#endif
#if !SERIAL_UART4_USED && defined(UART4_TX_PIN)
# undef UART4_TX_PIN
#endif
#if SERIAL_UART4_USED && !defined(INVERTER_PIN_UART4)
# define INVERTER_PIN_UART4 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART4_USED && defined(INVERTER_PIN_UART4)
# warning "INVERTER_PIN_UART4 is defined but UART4 is not enabled"
#endif
#if !SERIAL_UART4_USED && defined(INVERTER_PIN_UART4)
# undef INVERTER_PIN_UART4
#endif
#if SERIAL_UART5_USED && !defined(UART5_RX_PIN)
# define UART5_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART5_USED && defined(UART5_RX_PIN)
# warning "UART5_RX_PIN is defined but UART5 is not enabled"
#endif
#if !SERIAL_UART5_USED && defined(UART5_RX_PIN)
# undef UART5_RX_PIN
#endif
#if SERIAL_UART5_USED && !defined(UART5_TX_PIN)
# define UART5_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART5_USED && defined(UART5_TX_PIN)
# warning "UART5_TX_PIN is defined but UART5 is not enabled"
#endif
#if !SERIAL_UART5_USED && defined(UART5_TX_PIN)
# undef UART5_TX_PIN
#endif
#if SERIAL_UART5_USED && !defined(INVERTER_PIN_UART5)
# define INVERTER_PIN_UART5 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART5_USED && defined(INVERTER_PIN_UART5)
# warning "INVERTER_PIN_UART5 is defined but UART5 is not enabled"
#endif
#if !SERIAL_UART5_USED && defined(INVERTER_PIN_UART5)
# undef INVERTER_PIN_UART5
#endif
#if SERIAL_UART6_USED && !defined(UART6_RX_PIN)
# define UART6_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART6_USED && defined(UART6_RX_PIN)
# warning "UART6_RX_PIN is defined but UART6 is not enabled"
#endif
#if !SERIAL_UART6_USED && defined(UART6_RX_PIN)
# undef UART6_RX_PIN
#endif
#if SERIAL_UART6_USED && !defined(UART6_TX_PIN)
# define UART6_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART6_USED && defined(UART6_TX_PIN)
# warning "UART6_TX_PIN is defined but UART6 is not enabled"
#endif
#if !SERIAL_UART6_USED && defined(UART6_TX_PIN)
# undef UART6_TX_PIN
#endif
#if SERIAL_UART6_USED && !defined(INVERTER_PIN_UART6)
# define INVERTER_PIN_UART6 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART6_USED && defined(INVERTER_PIN_UART6)
# warning "INVERTER_PIN_UART6 is defined but UART6 is not enabled"
#endif
#if !SERIAL_UART6_USED && defined(INVERTER_PIN_UART6)
# undef INVERTER_PIN_UART6
#endif
#if SERIAL_UART7_USED && !defined(UART7_RX_PIN)
# define UART7_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART7_USED && defined(UART7_RX_PIN)
# warning "UART7_RX_PIN is defined but UART7 is not enabled"
#endif
#if !SERIAL_UART7_USED && defined(UART7_RX_PIN)
# undef UART7_RX_PIN
#endif
#if SERIAL_UART7_USED && !defined(UART7_TX_PIN)
# define UART7_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART7_USED && defined(UART7_TX_PIN)
# warning "UART7_TX_PIN is defined but UART7 is not enabled"
#endif
#if !SERIAL_UART7_USED && defined(UART7_TX_PIN)
# undef UART7_TX_PIN
#endif
#if SERIAL_UART7_USED && !defined(INVERTER_PIN_UART7)
# define INVERTER_PIN_UART7 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART7_USED && defined(INVERTER_PIN_UART7)
# warning "INVERTER_PIN_UART7 is defined but UART7 is not enabled"
#endif
#if !SERIAL_UART7_USED && defined(INVERTER_PIN_UART7)
# undef INVERTER_PIN_UART7
#endif
#if SERIAL_UART8_USED && !defined(UART8_RX_PIN)
# define UART8_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART8_USED && defined(UART8_RX_PIN)
# warning "UART8_RX_PIN is defined but UART8 is not enabled"
#endif
#if !SERIAL_UART8_USED && defined(UART8_RX_PIN)
# undef UART8_RX_PIN
#endif
#if SERIAL_UART8_USED && !defined(UART8_TX_PIN)
# define UART8_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART8_USED && defined(UART8_TX_PIN)
# warning "UART8_TX_PIN is defined but UART8 is not enabled"
#endif
#if !SERIAL_UART8_USED && defined(UART8_TX_PIN)
# undef UART8_TX_PIN
#endif
#if SERIAL_UART8_USED && !defined(INVERTER_PIN_UART8)
# define INVERTER_PIN_UART8 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART8_USED && defined(INVERTER_PIN_UART8)
# warning "INVERTER_PIN_UART8 is defined but UART8 is not enabled"
#endif
#if !SERIAL_UART8_USED && defined(INVERTER_PIN_UART8)
# undef INVERTER_PIN_UART8
#endif
#if SERIAL_UART9_USED && !defined(UART9_RX_PIN)
# define UART9_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART9_USED && defined(UART9_RX_PIN)
# warning "UART9_RX_PIN is defined but UART9 is not enabled"
#endif
#if !SERIAL_UART9_USED && defined(UART9_RX_PIN)
# undef UART9_RX_PIN
#endif
#if SERIAL_UART9_USED && !defined(UART9_TX_PIN)
# define UART9_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART9_USED && defined(UART9_TX_PIN)
# warning "UART9_TX_PIN is defined but UART9 is not enabled"
#endif
#if !SERIAL_UART9_USED && defined(UART9_TX_PIN)
# undef UART9_TX_PIN
#endif
#if SERIAL_UART9_USED && !defined(INVERTER_PIN_UART9)
# define INVERTER_PIN_UART9 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART9_USED && defined(INVERTER_PIN_UART9)
# warning "INVERTER_PIN_UART9 is defined but UART9 is not enabled"
#endif
#if !SERIAL_UART9_USED && defined(INVERTER_PIN_UART9)
# undef INVERTER_PIN_UART9
#endif
#if SERIAL_UART10_USED && !defined(UART10_RX_PIN)
# define UART10_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART10_USED && defined(UART10_RX_PIN)
# warning "UART10_RX_PIN is defined but UART10 is not enabled"
#endif
#if !SERIAL_UART10_USED && defined(UART10_RX_PIN)
# undef UART10_RX_PIN
#endif
#if SERIAL_UART10_USED && !defined(UART10_TX_PIN)
# define UART10_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART10_USED && defined(UART10_TX_PIN)
# warning "UART10_TX_PIN is defined but UART10 is not enabled"
#endif
#if !SERIAL_UART10_USED && defined(UART10_TX_PIN)
# undef UART10_TX_PIN
#endif
#if SERIAL_UART10_USED && !defined(INVERTER_PIN_UART10)
# define INVERTER_PIN_UART10 NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_UART10_USED && defined(INVERTER_PIN_UART10)
# warning "INVERTER_PIN_UART10 is defined but UART10 is not enabled"
#endif
#if !SERIAL_UART10_USED && defined(INVERTER_PIN_UART10)
# undef INVERTER_PIN_UART10
#endif
/**** LPUART *****/
#if defined(USE_LPUART1)
# define SERIAL_LPUART1_USED 1
#else
# define SERIAL_LPUART1_USED 0
#endif
#define SERIAL_LPUART_MASK ((SERIAL_LPUART1_USED * BIT(1 - 1)))
#define SERIAL_LPUART_COUNT (SERIAL_LPUART1_USED)
// 0 if no port is defined
#define SERIAL_LPUART_MAX (SERIAL_LPUART_MASK ? LOG2(SERIAL_LPUART_MASK) + 1 : 0)
// Normalize LPUART TX/RX
#if SERIAL_LPUART1_USED && !defined(LPUART1_RX_PIN)
# define LPUART1_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_LPUART1_USED && defined(LPUART1_RX_PIN)
# warning "LPUART1_RX_PIN is defined but LPUART1 is not enabled"
#endif
#if !SERIAL_LPUART1_USED && defined(LPUART1_RX_PIN)
# undef LPUART1_RX_PIN
#endif
#if SERIAL_LPUART1_USED && !defined(LPUART1_TX_PIN)
# define LPUART1_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_LPUART1_USED && defined(LPUART1_TX_PIN)
# warning "LPUART1_TX_PIN is defined but LPUART1 is not enabled"
#endif
#if !SERIAL_LPUART1_USED && defined(LPUART1_TX_PIN)
# undef LPUART1_TX_PIN
#endif
/**** SOFTSERIAL *****/
#if defined(USE_SOFTSERIAL)
# if !defined(USE_SOFTSERIAL1)
# define USE_SOFTSERIAL1
# endif
# if !defined(USE_SOFTSERIAL2)
# define USE_SOFTSERIAL2
# endif
#endif
#if defined(USE_SOFTSERIAL1)
# define SERIAL_SOFTSERIAL1_USED 1
#else
# define SERIAL_SOFTSERIAL1_USED 0
#endif
#if defined(USE_SOFTSERIAL2)
# define SERIAL_SOFTSERIAL2_USED 1
#else
# define SERIAL_SOFTSERIAL2_USED 0
#endif
#define SERIAL_SOFTSERIAL_MASK ((SERIAL_SOFTSERIAL1_USED * BIT(1 - 1)) | (SERIAL_SOFTSERIAL2_USED * BIT(2 - 1)))
#define SERIAL_SOFTSERIAL_COUNT (SERIAL_SOFTSERIAL1_USED + SERIAL_SOFTSERIAL2_USED)
// 0 if no port is defined
#define SERIAL_SOFTSERIAL_MAX (SERIAL_SOFTSERIAL_MASK ? LOG2(SERIAL_SOFTSERIAL_MASK) + 1 : 0)
#if SERIAL_SOFTSERIAL_COUNT != SERIAL_SOFTSERIAL_MAX
# error SOFTSERIAL ports must start with SOFTSERIAL1 and be continuous
#endif
// Normalize SOFTSERIAL TX/RX
#if SERIAL_SOFTSERIAL1_USED && !defined(SOFTSERIAL1_RX_PIN)
# define SOFTSERIAL1_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_SOFTSERIAL1_USED && defined(SOFTSERIAL1_RX_PIN)
# warning "SOFTSERIAL1_RX_PIN is defined but SOFTSERIAL1 is not enabled"
#endif
#if !SERIAL_SOFTSERIAL1_USED && defined(SOFTSERIAL1_RX_PIN)
# undef SOFTSERIAL1_RX_PIN
#endif
#if SERIAL_SOFTSERIAL1_USED && !defined(SOFTSERIAL1_TX_PIN)
# define SOFTSERIAL1_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_SOFTSERIAL1_USED && defined(SOFTSERIAL1_TX_PIN)
# warning "SOFTSERIAL1_TX_PIN is defined but SOFTSERIAL1 is not enabled"
#endif
#if !SERIAL_SOFTSERIAL1_USED && defined(SOFTSERIAL1_TX_PIN)
# undef SOFTSERIAL1_TX_PIN
#endif
#if SERIAL_SOFTSERIAL2_USED && !defined(SOFTSERIAL2_RX_PIN)
# define SOFTSERIAL2_RX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_SOFTSERIAL2_USED && defined(SOFTSERIAL2_RX_PIN)
# warning "SOFTSERIAL2_RX_PIN is defined but SOFTSERIAL2 is not enabled"
#endif
#if !SERIAL_SOFTSERIAL2_USED && defined(SOFTSERIAL2_RX_PIN)
# undef SOFTSERIAL2_RX_PIN
#endif
#if SERIAL_SOFTSERIAL2_USED && !defined(SOFTSERIAL2_TX_PIN)
# define SOFTSERIAL2_TX_PIN NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_SOFTSERIAL2_USED && defined(SOFTSERIAL2_TX_PIN)
# warning "SOFTSERIAL2_TX_PIN is defined but SOFTSERIAL2 is not enabled"
#endif
#if !SERIAL_SOFTSERIAL2_USED && defined(SOFTSERIAL2_TX_PIN)
# undef SOFTSERIAL2_TX_PIN
#endif
/**** VCP *****/
#if defined(USE_VCP)
# define SERIAL_VCP_USED 1
#else
# define SERIAL_VCP_USED 0
#endif
// set one bit if port is enabled for consistency
#define SERIAL_VCP_MASK (SERIAL_VCP_USED * BIT(0))
#define SERIAL_VCP_COUNT (SERIAL_VCP_USED)
// 0 if no port is defined
#define SERIAL_VCP_MAX (SERIAL_VCP_MASK ? LOG2(SERIAL_VCP_MASK) + 1 : 0)
// normalize USE_x after all ports are enumerated (x_COUNT of dependencies must be available)
#if !defined(USE_UART) && (SERIAL_UART_COUNT || SERIAL_LPUART_COUNT)
# define USE_UART
#endif
#if !defined(USE_LPUART) && (SERIAL_LPUART_COUNT)
# define USE_LPUART
#endif
#if !defined(USE_SOFTSERIAL) && (SERIAL_SOFTSERIAL_COUNT)
# define USE_SOFTSERIAL
#endif
#if !defined(USE_VCP) && (SERIAL_VCP_COUNT)
# define USE_VCP
#endif

View file

@ -372,13 +372,13 @@ static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_e
if (telemetryConfig()->halfDuplex) {
portOptions |= SERIAL_BIDIR;
}
// TODO - identifier is set only after opening port
hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, NULL, HOTT_BAUDRATE, mode, portOptions);
}
static bool hottIsUsingHardwareUART(void)
{
return !(portConfig->identifier == SERIAL_PORT_SOFTSERIAL1 || portConfig->identifier == SERIAL_PORT_SOFTSERIAL2);
return serialType(portConfig->identifier) != SERIALTYPE_SOFTSERIAL;
}
static void hottConfigurePortForTX(void)

View file

@ -487,7 +487,9 @@ static void freeSmartPortTelemetryPort(void)
static void configureSmartPortTelemetryPort(void)
{
if (portConfig) {
portOptions_e portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED);
// On SmartPort, SERIAL_INVERTED is default
const portOptions_e portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : 0)
| (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED);
smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions);
}

View file

@ -30,6 +30,7 @@
#include "drivers/dma_reqmap.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#include "pg/timerio.h"
@ -69,20 +70,30 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
{ DMA_PERIPH_SDIO, 0, { DMA(2, 3, 4), DMA(2, 6, 4) } },
#endif // USE_SDCARD_SDIO
#ifdef USE_UART
#ifdef USE_UART1
{ DMA_PERIPH_UART_TX, UARTDEV_1, { DMA(2, 7, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_1, { DMA(2, 5, 4), DMA(2, 2, 4) } },
#endif
#ifdef USE_UART2
{ DMA_PERIPH_UART_TX, UARTDEV_2, { DMA(1, 6, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_2, { DMA(1, 5, 4) } },
#endif
#ifdef USE_UART3
{ DMA_PERIPH_UART_TX, UARTDEV_3, { DMA(1, 3, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_3, { DMA(1, 1, 4) } },
#endif
#ifdef USE_UART4
{ DMA_PERIPH_UART_TX, UARTDEV_4, { DMA(1, 4, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_4, { DMA(1, 2, 4) } },
#endif
#ifdef USE_UART5
{ DMA_PERIPH_UART_TX, UARTDEV_5, { DMA(1, 7, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_5, { DMA(1, 0, 4) } },
#endif
#ifdef USE_UART6
{ DMA_PERIPH_UART_TX, UARTDEV_6, { DMA(2, 6, 5), DMA(2, 7, 5) } },
{ DMA_PERIPH_UART_RX, UARTDEV_6, { DMA(2, 1, 5), DMA(2, 2, 5) } },
#endif // USE_UART
#endif
};
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)

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

View file

@ -26,7 +26,6 @@
#include <stdint.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_UART
@ -45,7 +44,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -55,13 +54,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1_TX_DMA
.txDMAResource = (dmaResource_t *)DMA2_Stream7,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA10), GPIO_AF7_USART1 },
{ DEFIO_TAG_E(PB7), GPIO_AF7_USART1 },
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
},
.txPins = {
{ DEFIO_TAG_E(PA9), GPIO_AF7_USART1 },
{ DEFIO_TAG_E(PB6), GPIO_AF7_USART1 },
.txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
},
.af = GPIO_AF7_USART1,
.rcc = RCC_APB2(USART1),
@ -77,7 +72,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -87,14 +82,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2_TX_DMA
.txDMAResource = (dmaResource_t *)DMA1_Stream6,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA3), GPIO_AF7_USART2 },
{ DEFIO_TAG_E(PD6), GPIO_AF7_USART2 }
},
.txPins = {
{ DEFIO_TAG_E(PA2), GPIO_AF7_USART2 },
{ DEFIO_TAG_E(PD5), GPIO_AF7_USART2 }
},
.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,
@ -109,7 +98,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -119,16 +108,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3_TX_DMA
.txDMAResource = (dmaResource_t *)DMA1_Stream3,
#endif
.rxPins = {
{ DEFIO_TAG_E(PB11), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PC11), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PD9), GPIO_AF7_USART3 }
},
.txPins = {
{ DEFIO_TAG_E(PB10), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PC10), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PD8), GPIO_AF7_USART3 }
},
.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,
@ -143,7 +124,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -153,14 +134,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4_TX_DMA
.txDMAResource = (dmaResource_t *)DMA1_Stream4,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA1), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 }
},
.txPins = {
{ DEFIO_TAG_E(PA0), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 }
},
.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,
@ -175,7 +150,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -185,12 +160,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5_TX_DMA
.txDMAResource = (dmaResource_t *)DMA1_Stream7,
#endif
.rxPins = {
{ DEFIO_TAG_E(PD2), GPIO_AF8_UART5 }
},
.txPins = {
{ DEFIO_TAG_E(PC12), GPIO_AF8_UART5 }
},
.rxPins = { { DEFIO_TAG_E(PD2) } },
.txPins = { { DEFIO_TAG_E(PC12) } },
.af = GPIO_AF8_UART5,
.rcc = RCC_APB1(UART5),
.irqn = UART5_IRQn,
@ -205,7 +176,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
@ -215,14 +186,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6_TX_DMA
.txDMAResource = (dmaResource_t *)DMA2_Stream6,
#endif
.rxPins = {
{ DEFIO_TAG_E(PC7), GPIO_AF8_USART6 },
{ DEFIO_TAG_E(PG9), GPIO_AF8_USART6 }
},
.txPins = {
{ DEFIO_TAG_E(PC6), GPIO_AF8_USART6 },
{ DEFIO_TAG_E(PG14), GPIO_AF8_USART6 }
},
.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,
@ -236,83 +201,130 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
};
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
bool checkUsartTxOutput(uartPort_t *s)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartDevice_t *uart = container_of(s, uartDevice_t, port);
IO_t txIO = IOGetByTag(uart->tx.pin);
uartPort_t *s = &(uartdev->port);
if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
if (IORead(txIO)) {
// TX is high so we're good to transmit
s->port.vTable = uartVTable;
// Enable USART TX output
uart->txPinState = TX_PIN_ACTIVE;
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->hardware->af);
s->port.baudRate = baudRate;
// Enable the UART transmitter
SET_BIT(s->Handle.Instance->CTRL1, USART_CTRL1_TXEN);
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
if ((options & SERIAL_BIDIR) && txIO) {
ioConfig_t ioCfg = IO_CONFIG(
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PULLDOWN : GPIO_PULLUP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
}
else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_MONITOR;
// Switch TX to UART output whilst UART sends idle preamble
checkUsartTxOutput(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
return true;
} else {
// TX line is pulled low so don't enable USART TX
return false;
}
}
#ifdef USE_DMA
if (!s->rxDMAResource) {
DAL_NVIC_SetPriority(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
DAL_NVIC_EnableIRQ(hardware->irqn);
}
#endif
return s;
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

View file

@ -49,8 +49,6 @@
#define USE_UART5
#define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6)
#define USE_INVERTER
#define USE_SPI_DEVICE_1

View file

@ -49,8 +49,6 @@
#define USE_UART5
#define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6)
#define USE_INVERTER
#define USE_SPI_DEVICE_1

View file

@ -31,7 +31,7 @@
#include "drivers/dma_reqmap.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#include "pg/timerio.h"
typedef struct dmaPeripheralMapping_s {
@ -97,17 +97,28 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
REQMAP(ADC, 3),
#endif
#ifdef USE_UART
// UARTDEV_x enum value exists only when coresponding UART is enabled
#ifdef USE_UART1
REQMAP_DIR(UART, 1, TX),
REQMAP_DIR(UART, 1, RX),
#endif
#ifdef USE_UART2
REQMAP_DIR(UART, 2, TX),
REQMAP_DIR(UART, 2, RX),
#endif
#ifdef USE_UART3
REQMAP_DIR(UART, 3, TX),
REQMAP_DIR(UART, 3, RX),
#endif
#ifdef USE_UART4
REQMAP_DIR(UART, 4, TX),
REQMAP_DIR(UART, 4, RX),
#endif
#ifdef USE_UART5
REQMAP_DIR(UART, 5, TX),
REQMAP_DIR(UART, 5, RX),
#endif
#ifdef USE_UART6
REQMAP_DIR(UART, 6, TX),
REQMAP_DIR(UART, 6, RX),
#endif

View file

@ -48,40 +48,9 @@
#include "drivers/serial_uart.h"
#include "drivers/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
#endif
}
static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
{
for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
uartDevice_t *candidate = uartDevmap[i];
if (&candidate->port == uartPort) {
return candidate;
}
}
return NULL;
}
static void uartConfigurePinSwap(uartPort_t *uartPort)
{
uartDevice_t *uartDevice = uartFindDevice(uartPort);
if (!uartDevice) {
return;
}
uartDevice_t *uartDevice = container_of(uartPort, uartDevice_t, port);
if (uartDevice->pinSwap) {
usart_transmit_receive_pin_swap(uartDevice->port.USARTx, TRUE);
}
@ -112,10 +81,10 @@ void uartReconfigure(uartPort_t *uartPort)
usart_transmitter_enable(uartPort->USARTx, TRUE);
}
//config pin inverter
usartConfigurePinInversion(uartPort);
// config external pin inverter (no internal pin inversion available)
uartConfigureExternalPinInversion(uartPort);
//config pin swap
// config pin swap
uartConfigurePinSwap(uartPort);
if (uartPort->port.options & SERIAL_BIDIR) {
@ -132,16 +101,16 @@ void uartReconfigure(uartPort_t *uartPort)
if (uartPort->rxDMAResource) {
dma_default_para_init(&DMA_InitStructure);
DMA_InitStructure.loop_mode_enable=TRUE;
DMA_InitStructure.peripheral_base_addr=uartPort->rxDMAPeripheralBaseAddr;
DMA_InitStructure.loop_mode_enable = TRUE;
DMA_InitStructure.peripheral_base_addr = uartPort->rxDMAPeripheralBaseAddr;
DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM;
DMA_InitStructure.peripheral_inc_enable =FALSE;
DMA_InitStructure.peripheral_data_width =DMA_PERIPHERAL_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_inc_enable =TRUE;
DMA_InitStructure.peripheral_inc_enable = FALSE;
DMA_InitStructure.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_inc_enable = TRUE;
DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_base_addr=(uint32_t)uartPort->port.rxBuffer;
DMA_InitStructure.memory_base_addr = (uint32_t)uartPort->port.rxBuffer;
DMA_InitStructure.buffer_size = uartPort->port.rxBufferSize;
DMA_InitStructure.direction= DMA_DIR_PERIPHERAL_TO_MEMORY;
DMA_InitStructure.direction = DMA_DIR_PERIPHERAL_TO_MEMORY;
xDMA_DeInit(uartPort->rxDMAResource);
xDMA_Init(uartPort->rxDMAResource, &DMA_InitStructure);
@ -159,16 +128,16 @@ void uartReconfigure(uartPort_t *uartPort)
if (uartPort->port.mode & MODE_TX) {
if (uartPort->txDMAResource) {
dma_default_para_init(&DMA_InitStructure);
DMA_InitStructure.loop_mode_enable=FALSE;
DMA_InitStructure.peripheral_base_addr=uartPort->txDMAPeripheralBaseAddr;
DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM;
DMA_InitStructure.peripheral_inc_enable =FALSE;
DMA_InitStructure.peripheral_data_width =DMA_PERIPHERAL_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_inc_enable =TRUE;
DMA_InitStructure.loop_mode_enable = FALSE;
DMA_InitStructure.peripheral_base_addr = uartPort->txDMAPeripheralBaseAddr;
DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM;
DMA_InitStructure.peripheral_inc_enable = FALSE;
DMA_InitStructure.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_inc_enable = TRUE;
DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
DMA_InitStructure.memory_base_addr=(uint32_t)uartPort->port.txBuffer;
DMA_InitStructure.memory_base_addr = (uint32_t)uartPort->port.txBuffer;
DMA_InitStructure.buffer_size = uartPort->port.txBufferSize;
DMA_InitStructure.direction= DMA_DIR_MEMORY_TO_PERIPHERAL;
DMA_InitStructure.direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
xDMA_DeInit(uartPort->txDMAResource);
xDMA_Init(uartPort->txDMAResource, &DMA_InitStructure);
@ -181,7 +150,7 @@ void uartReconfigure(uartPort_t *uartPort)
}
usart_interrupt_enable(uartPort->USARTx, USART_TDC_INT, TRUE);
}
// TODO: usart_enable is called twice
usart_enable(uartPort->USARTx,TRUE);
}

View file

@ -89,7 +89,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART1_RX,
@ -120,7 +120,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART2_RX,
@ -151,7 +151,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART3_RX,
@ -182,7 +182,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART4_RX,
@ -213,7 +213,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART5_RX,
@ -246,7 +246,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART6_RX,
@ -279,7 +279,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART7
{
.device = UARTDEV_7,
.identifier = SERIAL_PORT_UART7,
.reg = UART7,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART7_RX,
@ -313,7 +313,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART8
{
.device = UARTDEV_8,
.identifier = SERIAL_PORT_UART8,
.reg = UART8, //USE UART8 FOR PIN CONFIG
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART8_RX,
@ -348,79 +348,4 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
};
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartPort_t *s = &(uartdev->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
if ((options & SERIAL_BIDIR) && txIO) {
//mode,speed,otype,pupd
ioConfig_t ioCfg = IO_CONFIG(
GPIO_MODE_MUX,
GPIO_DRIVE_STRENGTH_STRONGER,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_OUTPUT_PUSH_PULL : GPIO_OUTPUT_OPEN_DRAIN,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PULL_DOWN : GPIO_PULL_UP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
}
}
#ifdef USE_DMA
if (!s->rxDMAResource)
#endif
{
nvic_irq_enable(hardware->irqn,NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
}
return s;
}
#endif // USE_UART

View file

@ -40,8 +40,6 @@
#define USE_VCP
#define UNIFIED_SERIAL_PORT_COUNT 1
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -51,8 +49,6 @@
#define USE_UART7
#define USE_UART8
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -40,8 +40,6 @@
#define USE_VCP
#define UNIFIED_SERIAL_PORT_COUNT 1
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -51,8 +49,6 @@
#define USE_UART7
#define USE_UART8
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -92,8 +92,6 @@
#define USE_UART7
#define USE_UART8
#define SERIAL_PORT_COUNT 8
#define DEFAULT_RX_FEATURE FEATURE_RX_MSP
#define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_TELEMETRY)

View file

@ -372,7 +372,7 @@ void adcInit(const adcConfig_t *config)
RCC_ClockCmd(adc->rccADC, ENABLE);
int configuredAdcChannels = BITCOUNT(adc->channelBits);
int configuredAdcChannels = popcount(adc->channelBits);
adcInitDevice(adc, configuredAdcChannels);
@ -472,11 +472,11 @@ void adcInit(const adcConfig_t *config)
// Start conversion in DMA mode
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t *)&adcConversionBuffer[dmaBufferIndex], BITCOUNT(adc->channelBits)) != HAL_OK) {
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t *)&adcConversionBuffer[dmaBufferIndex], popcount(adc->channelBits)) != HAL_OK) {
handleError();
}
dmaBufferIndex += BITCOUNT(adc->channelBits);
dmaBufferIndex += popcount(adc->channelBits);
}
}

View file

@ -424,7 +424,7 @@ void adcInit(const adcConfig_t *config)
__HAL_RCC_ADC_CONFIG(RCC_ADCCLKSOURCE_CLKP);
#endif
int configuredAdcChannels = BITCOUNT(adc->channelBits);
int configuredAdcChannels = popcount(adc->channelBits);
adcInitDevice(adc, configuredAdcChannels);
@ -529,11 +529,11 @@ void adcInit(const adcConfig_t *config)
// Start conversion in DMA mode
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t *)&adcConversionBuffer[dmaBufferIndex], BITCOUNT(adc->channelBits)) != HAL_OK) {
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t *)&adcConversionBuffer[dmaBufferIndex], popcount(adc->channelBits)) != HAL_OK) {
errorHandler();
}
dmaBufferIndex += BITCOUNT(adc->channelBits);
dmaBufferIndex += popcount(adc->channelBits);
}
}

View file

@ -127,6 +127,7 @@ static const uint32_t quadSpi_addressSizeMap[] = {
static uint32_t quadSpi_addressSizeFromValue(uint8_t addressSize)
{
// TODO addressSize + 7) / 8)
return quadSpi_addressSizeMap[((addressSize + 1) / 8) - 1]; // rounds to nearest QSPI_ADDRESS_* value that will hold the address.
}

View file

@ -30,6 +30,7 @@
#include "drivers/dma_reqmap.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#include "pg/timerio.h"
@ -98,21 +99,29 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
REQMAP(ADC, 5),
#endif
#ifdef USE_UART
#ifdef USE_UART1
REQMAP_DIR(UART, 1, TX),
REQMAP_DIR(UART, 1, RX),
#endif
#ifdef USE_UART2
REQMAP_DIR(UART, 2, TX),
REQMAP_DIR(UART, 2, RX),
#endif
#ifdef USE_UART3
REQMAP_DIR(UART, 3, TX),
REQMAP_DIR(UART, 3, RX),
#endif
#ifdef USE_UART4
REQMAP_DIR(UART, 4, TX),
REQMAP_DIR(UART, 4, RX),
#endif
#ifdef USE_UART5
REQMAP_DIR(UART, 5, TX),
REQMAP_DIR(UART, 5, RX),
#ifdef USE_LPUART1
{ DMA_PERIPH_UART_TX, LPUARTDEV_1, DMA_REQUEST_LPUART1_TX },
{ DMA_PERIPH_UART_RX, LPUARTDEV_1, DMA_REQUEST_LPUART1_RX },
#endif
#ifdef USE_LPUART1
{ DMA_PERIPH_UART_TX, UARTDEV_LP1, DMA_REQUEST_LPUART1_TX },
{ DMA_PERIPH_UART_RX, UARTDEV_LP1, DMA_REQUEST_LPUART1_RX },
#endif
#ifdef USE_TIMER
@ -256,33 +265,49 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
#endif
#endif
#ifdef USE_UART
#ifdef USE_UART1
REQMAP_DIR(UART, 1, TX),
REQMAP_DIR(UART, 1, RX),
#endif
#ifdef USE_UART2
REQMAP_DIR(UART, 2, TX),
REQMAP_DIR(UART, 2, RX),
#endif
#ifdef USE_UART3
REQMAP_DIR(UART, 3, TX),
REQMAP_DIR(UART, 3, RX),
#endif
#ifdef USE_UART4
REQMAP_DIR(UART, 4, TX),
REQMAP_DIR(UART, 4, RX),
#endif
#ifdef USE_UART5
REQMAP_DIR(UART, 5, TX),
REQMAP_DIR(UART, 5, RX),
#endif
#ifdef USE_UART6
REQMAP_DIR(UART, 6, TX),
REQMAP_DIR(UART, 6, RX),
#endif
#ifdef USE_UART7
REQMAP_DIR(UART, 7, TX),
REQMAP_DIR(UART, 7, RX),
#endif
#ifdef USE_UART8
REQMAP_DIR(UART, 8, TX),
REQMAP_DIR(UART, 8, RX),
#if defined(STM32H7A3xxQ)
#endif
#ifdef USE_UART9
REQMAP_DIR(UART, 9, TX),
REQMAP_DIR(UART, 9, RX),
#endif
#ifdef USE_UART10
REQMAP_DIR(UART, 10, TX),
REQMAP_DIR(UART, 10, RX),
#endif
#ifdef USE_LPUART1
{ DMA_PERIPH_UART_TX, LPUARTDEV_1, BDMA_REQUEST_LPUART1_TX },
{ DMA_PERIPH_UART_RX, LPUARTDEV_1, BDMA_REQUEST_LPUART1_RX },
#endif
{ DMA_PERIPH_UART_TX, UARTDEV_LP1, BDMA_REQUEST_LPUART1_TX },
{ DMA_PERIPH_UART_RX, UARTDEV_LP1, BDMA_REQUEST_LPUART1_RX },
#endif
#ifdef USE_TIMER
@ -414,17 +439,27 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
{ DMA_PERIPH_SDIO, 0, { DMA(2, 3, 4), DMA(2, 6, 4) } },
#endif
#ifdef USE_UART
#ifdef USE_UART1
{ DMA_PERIPH_UART_TX, UARTDEV_1, { DMA(2, 7, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_1, { DMA(2, 5, 4), DMA(2, 2, 4) } },
#endif
#ifdef USE_UART2
{ DMA_PERIPH_UART_TX, UARTDEV_2, { DMA(1, 6, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_2, { DMA(1, 5, 4) } },
#endif
#ifdef USE_UART3
{ DMA_PERIPH_UART_TX, UARTDEV_3, { DMA(1, 3, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_3, { DMA(1, 1, 4) } },
#endif
#ifdef USE_UART4
{ DMA_PERIPH_UART_TX, UARTDEV_4, { DMA(1, 4, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_4, { DMA(1, 2, 4) } },
#endif
#ifdef USE_UART5
{ DMA_PERIPH_UART_TX, UARTDEV_5, { DMA(1, 7, 4) } },
{ DMA_PERIPH_UART_RX, UARTDEV_5, { DMA(1, 0, 4) } },
#endif
#ifdef USE_UART6
{ DMA_PERIPH_UART_TX, UARTDEV_6, { DMA(2, 6, 5), DMA(2, 7, 5) } },
{ DMA_PERIPH_UART_RX, UARTDEV_6, { DMA(2, 1, 5), DMA(2, 2, 5) } },
#endif
@ -485,8 +520,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, ui
return NULL;
}
for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) {
const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i];
for (const dmaPeripheralMapping_t *periph = dmaPeripheralMapping; periph < ARRAYEND(dmaPeripheralMapping) ; periph++) {
#if defined(STM32H7) || defined(STM32G4)
if (periph->device == device && periph->index == index) {
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];

View file

@ -22,6 +22,7 @@
#pragma once
#if defined(STM32H7) || defined(STM32G4)
#define MAX_PERIPHERAL_DMA_OPTIONS 16
#define MAX_TIMER_DMA_OPTIONS 16
#else

View file

@ -67,26 +67,10 @@ static void usartConfigurePinInversion(uartPort_t *uartPort)
}
}
static uartDevice_t *uartFindDevice(const uartPort_t *uartPort)
{
for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
uartDevice_t *candidate = uartDevmap[i];
if (&candidate->port == uartPort) {
return candidate;
}
}
return NULL;
}
#if !(defined(STM32F4))
#if UART_TRAIT_PINSWAP
static void uartConfigurePinSwap(uartPort_t *uartPort)
{
uartDevice_t *uartDevice = uartFindDevice(uartPort);
if (!uartDevice) {
return;
}
uartDevice_t *uartDevice = container_of(uartPort, uartDevice_t, port);
if (uartDevice->pinSwap) {
uartDevice->port.Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_SWAP_INIT;
uartDevice->port.Handle.AdvancedInit.Swap = UART_ADVFEATURE_SWAP_ENABLE;
@ -130,12 +114,9 @@ void uartReconfigure(uartPort_t *uartPort)
usartTargetConfigure(uartPort);
#endif
if (uartPort->port.options & SERIAL_BIDIR)
{
if (uartPort->port.options & SERIAL_BIDIR) {
HAL_HalfDuplex_Init(&uartPort->Handle);
}
else
{
} else {
HAL_UART_Init(&uartPort->Handle);
}

View file

@ -48,22 +48,6 @@
#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
}
void uartReconfigure(uartPort_t *uartPort)
{
USART_InitTypeDef USART_InitStructure;
@ -91,7 +75,8 @@ void uartReconfigure(uartPort_t *uartPort)
USART_Init(uartPort->USARTx, &USART_InitStructure);
usartConfigurePinInversion(uartPort);
// config external pin inverter (no internal pin inversion available)
uartConfigureExternalPinInversion(uartPort);
if (uartPort->port.options & SERIAL_BIDIR)
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
@ -103,6 +88,7 @@ void uartReconfigure(uartPort_t *uartPort)
// Receive DMA or IRQ
DMA_InitTypeDef DMA_InitStructure;
if (uartPort->port.mode & MODE_RX) {
#ifdef USE_DMA
if (uartPort->rxDMAResource) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
@ -133,7 +119,9 @@ void uartReconfigure(uartPort_t *uartPort)
xDMA_Cmd(uartPort->rxDMAResource, ENABLE);
USART_DMACmd(uartPort->USARTx, USART_DMAReq_Rx, ENABLE);
uartPort->rxDMAPos = xDMA_GetCurrDataCounter(uartPort->rxDMAResource);
} else {
} else
#endif
{
USART_ClearITPendingBit(uartPort->USARTx, USART_IT_RXNE);
USART_ITConfig(uartPort->USARTx, USART_IT_RXNE, ENABLE);
USART_ITConfig(uartPort->USARTx, USART_IT_IDLE, ENABLE);
@ -142,6 +130,7 @@ void uartReconfigure(uartPort_t *uartPort)
// Transmit DMA or IRQ
if (uartPort->port.mode & MODE_TX) {
#ifdef USE_DMA
if (uartPort->txDMAResource) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
@ -177,14 +166,16 @@ void uartReconfigure(uartPort_t *uartPort)
xDMA_SetCurrDataCounter(uartPort->txDMAResource, 0);
USART_DMACmd(uartPort->USARTx, USART_DMAReq_Tx, ENABLE);
} else {
} else
#endif
{
USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
}
// Enable the interrupt so completion of the transmission will be signalled
USART_ITConfig(uartPort->USARTx, USART_IT_TC, ENABLE);
}
USART_Cmd(uartPort->USARTx, ENABLE);
USART_Cmd(uartPort->USARTx, ENABLE); // TODO : enabling twice?
}
#ifdef USE_DMA
@ -209,7 +200,7 @@ void uartTryStartTxDMA(uartPort_t *s)
}
if (s->port.txBufferHead == s->port.txBufferTail) {
// No more data to transmit.
// No more data to transmit
s->txDMAEmpty = true;
return;
}
@ -222,15 +213,16 @@ void uartTryStartTxDMA(uartPort_t *s)
DMAx_SetMemoryAddress(s->txDMAResource, (uint32_t)&s->port.txBuffer[s->port.txBufferTail]);
#endif
unsigned chunk;
if (s->port.txBufferHead > s->port.txBufferTail) {
xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferHead - s->port.txBufferTail);
chunk = s->port.txBufferHead - s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead;
} else {
xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferSize - s->port.txBufferTail);
chunk = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
xDMA_SetCurrDataCounter(s->txDMAResource, chunk);
reenable:
xDMA_Cmd(s->txDMAResource, ENABLE);
}

View file

@ -26,7 +26,6 @@
#include <stdint.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_UART
@ -45,7 +44,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
@ -79,7 +78,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
@ -105,7 +104,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
@ -131,7 +130,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
@ -157,7 +156,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
@ -183,7 +182,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
.rxDMAChannel = DMA_Channel_5,
.txDMAChannel = DMA_Channel_5,
@ -297,83 +296,6 @@ void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
}
}
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uart = uartDevmap[device];
if (!uart) return NULL;
const uartHardware_t *hardware = uart->hardware;
if (!hardware) return NULL; // XXX Can't happen !?
uartPort_t *s = &(uart->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->USARTx = hardware->reg;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uart);
#endif
IO_t txIO = IOGetByTag(uart->tx.pin);
IO_t rxIO = IOGetByTag(uart->rx.pin);
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
uart->txPinState = TX_PIN_IGNORE;
if (options & SERIAL_BIDIR) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, (options & SERIAL_BIDIR_PP_PD) ? IOCFG_AF_PP_PD
: (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP
: IOCFG_AF_OD, hardware->af);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (options & SERIAL_CHECK_TX) {
uart->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP_UP, hardware->af);
}
}
#ifdef USE_DMA
if (!(s->rxDMAResource)) {
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
#endif
return s;
}
void uartIrqHandler(uartPort_t *s)
{
if (!s->rxDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
@ -416,4 +338,4 @@ void uartIrqHandler(uartPort_t *s)
(void) s->USARTx->DR;
}
}
#endif
#endif // USE_UART

View file

@ -44,7 +44,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -69,7 +69,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
},
.rcc = RCC_APB2(USART1),
.rxIrq = USART1_IRQn,
.irqn = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
@ -81,7 +81,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -100,7 +100,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD5), GPIO_AF7_USART2 }
},
.rcc = RCC_APB1(USART2),
.rxIrq = USART2_IRQn,
.irqn = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
@ -112,7 +112,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -133,7 +133,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD8), GPIO_AF7_USART3 }
},
.rcc = RCC_APB1(USART3),
.rxIrq = USART3_IRQn,
.irqn = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
@ -145,7 +145,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -172,7 +172,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
},
.rcc = RCC_APB1(UART4),
.rxIrq = UART4_IRQn,
.irqn = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4,
.txBuffer = uart4TxBuffer,
@ -184,7 +184,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
@ -211,7 +211,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
},
.rcc = RCC_APB1(UART5),
.rxIrq = UART5_IRQn,
.irqn = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
@ -223,7 +223,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
@ -242,7 +242,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PG14), GPIO_AF8_USART6 }
},
.rcc = RCC_APB2(USART6),
.rxIrq = USART6_IRQn,
.irqn = USART6_IRQn,
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART6,
.txBuffer = uart6TxBuffer,
@ -254,7 +254,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART7
{
.device = UARTDEV_7,
.identifier = SERIAL_PORT_UART7,
.reg = UART7,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
@ -281,7 +281,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
},
.rcc = RCC_APB1(UART7),
.rxIrq = UART7_IRQn,
.irqn = UART7_IRQn,
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART7,
.txBuffer = uart7TxBuffer,
@ -293,7 +293,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART8
{
.device = UARTDEV_8,
.identifier = SERIAL_PORT_UART8,
.reg = UART8,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
@ -310,7 +310,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PE1), GPIO_AF8_UART8 }
},
.rcc = RCC_APB1(UART8),
.rxIrq = UART8_IRQn,
.irqn = UART8_IRQn,
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART8,
.txBuffer = uart8TxBuffer,
@ -321,83 +321,4 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
};
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartPort_t *s = &(uartdev->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
if ((options & SERIAL_BIDIR) && txIO) {
ioConfig_t ioCfg = IO_CONFIG(
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PULLDOWN : GPIO_PULLUP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
}
else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_MONITOR;
// Switch TX to UART output whilst UART sends idle preamble
checkUsartTxOutput(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
}
}
#ifdef USE_DMA
if (!s->rxDMAResource) {
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->rxIrq);
}
#endif
return s;
}
#endif // USE_UART

View file

@ -77,7 +77,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART1_RX,
@ -96,7 +96,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC4), GPIO_AF7_USART1 },
},
.rcc = RCC_APB2(USART1),
.rxIrq = USART1_IRQn,
.irqn = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
@ -108,7 +108,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART2_RX,
@ -127,7 +127,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PB3), GPIO_AF7_USART2 },
},
.rcc = RCC_APB11(USART2),
.rxIrq = USART2_IRQn,
.irqn = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
@ -139,7 +139,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART3_RX,
@ -158,7 +158,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC10), GPIO_AF7_USART3 },
},
.rcc = RCC_APB11(USART3),
.rxIrq = USART3_IRQn,
.irqn = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
@ -170,7 +170,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART4_RX,
@ -185,7 +185,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC10), GPIO_AF5_UART4 },
},
.rcc = RCC_APB11(UART4),
.rxIrq = UART4_IRQn,
.irqn = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4,
.txBuffer = uart4TxBuffer,
@ -197,7 +197,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART5_RX,
@ -212,7 +212,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC12), GPIO_AF5_UART5 },
},
.rcc = RCC_APB11(UART5),
.rxIrq = UART5_IRQn,
.irqn = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
@ -224,7 +224,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_LPUART1
{
.device = LPUARTDEV_1,
.identifier = SERIAL_PORT_LPUART1,
.reg = LPUART1,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_LPUART1_RX,
@ -243,95 +243,15 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC1), GPIO_AF8_LPUART1 },
},
.rcc = RCC_APB12(LPUART1),
.rxIrq = LPUART1_IRQn,
.irqn = LPUART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART6,
.txBuffer = lpuart1TxBuffer,
.rxBuffer = lpuart1RxBuffer,
.txBufferSize = sizeof(lpuart1TxBuffer),
.rxBufferSize = sizeof(lpuart1RxBuffer),
.txBuffer = uartLp1TxBuffer,
.rxBuffer = uartLp1RxBuffer,
.txBufferSize = sizeof(uartLp1TxBuffer),
.rxBufferSize = sizeof(uartLp1RxBuffer),
},
#endif
};
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartPort_t *s = &(uartdev->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
if ((options & SERIAL_BIDIR) && txIO) {
ioConfig_t ioCfg = IO_CONFIG(
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PULLDOWN : GPIO_PULLUP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
}
}
#ifdef USE_DMA
if (!s->rxDMAResource)
#endif
{
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->rxIrq);
}
return s;
}
#endif // USE_UART

View file

@ -103,7 +103,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART1_RX,
@ -122,7 +122,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PB14), GPIO_AF4_USART1 },
},
.rcc = RCC_APB2(USART1),
.rxIrq = USART1_IRQn,
.irqn = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
@ -134,7 +134,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART2_RX,
@ -151,7 +151,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD5), GPIO_AF7_USART2 }
},
.rcc = RCC_APB1L(USART2),
.rxIrq = USART2_IRQn,
.irqn = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
@ -163,7 +163,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART3_RX,
@ -182,7 +182,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD8), GPIO_AF7_USART3 }
},
.rcc = RCC_APB1L(USART3),
.rxIrq = USART3_IRQn,
.irqn = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
@ -194,7 +194,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART4_RX,
@ -217,7 +217,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD1), GPIO_AF8_UART4 }
},
.rcc = RCC_APB1L(UART4),
.rxIrq = UART4_IRQn,
.irqn = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4,
.txBuffer = uart4TxBuffer,
@ -229,7 +229,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART5_RX,
@ -248,7 +248,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PC12), GPIO_AF8_UART5 },
},
.rcc = RCC_APB1L(UART5),
.rxIrq = UART5_IRQn,
.irqn = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
@ -260,7 +260,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART6_RX,
@ -277,7 +277,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PG14), GPIO_AF7_USART6 }
},
.rcc = RCC_APB2(USART6),
.rxIrq = USART6_IRQn,
.irqn = USART6_IRQn,
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART6,
.txBuffer = uart6TxBuffer,
@ -289,7 +289,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART7
{
.device = UARTDEV_7,
.identifier = SERIAL_PORT_USART7,
.reg = UART7,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART7_RX,
@ -310,7 +310,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PF7), GPIO_AF7_UART7 },
},
.rcc = RCC_APB1L(UART7),
.rxIrq = UART7_IRQn,
.irqn = UART7_IRQn,
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART7,
.txBuffer = uart7TxBuffer,
@ -322,7 +322,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART8
{
.device = UARTDEV_8,
.identifier = SERIAL_PORT_USART8,
.reg = UART8,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART8_RX,
@ -337,7 +337,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PE1), GPIO_AF8_UART8 }
},
.rcc = RCC_APB1L(UART8),
.rxIrq = UART8_IRQn,
.irqn = UART8_IRQn,
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART8,
.txBuffer = uart8TxBuffer,
@ -349,7 +349,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART9
{
.device = UARTDEV_9,
.identifier = SERIAL_PORT_UART9,
.reg = UART9,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_UART9_RX,
@ -364,7 +364,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PD15), GPIO_AF11_UART9 }
},
.rcc = RCC_APB2(UART9),
.rxIrq = UART9_IRQn,
.irqn = UART9_IRQn,
.txPriority = NVIC_PRIO_SERIALUART9_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART9,
.txBuffer = uart9TxBuffer,
@ -376,7 +376,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART10
{
.device = UARTDEV_10,
.identifier = SERIAL_PORT_USART10,
.reg = USART10,
#ifdef USE_DMA
.rxDMAChannel = DMA_REQUEST_USART10_RX,
@ -391,7 +391,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PE3), GPIO_AF11_USART10 }
},
.rcc = RCC_APB2(USART10),
.rxIrq = USART10_IRQn,
.irqn = USART10_IRQn,
.txPriority = NVIC_PRIO_SERIALUART10_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART10,
.txBuffer = uart10TxBuffer,
@ -403,7 +403,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_LPUART1
{
.device = LPUARTDEV_1,
.identifier = SERIAL_PORT_LPUART1,
.reg = LPUART1,
#ifdef USE_DMA
.rxDMAChannel = BDMA_REQUEST_LPUART1_RX,
@ -420,95 +420,16 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PB6), GPIO_AF8_LPUART }
},
.rcc = RCC_APB4(LPUART1),
.rxIrq = LPUART1_IRQn,
.irqn = LPUART1_IRQn,
.txPriority = NVIC_PRIO_SERIALLPUART1_TXDMA, // Not used until DMA is supported
.rxPriority = NVIC_PRIO_SERIALLPUART1, // Not used until DMA is supported
.txBuffer = lpuart1TxBuffer,
.rxBuffer = lpuart1RxBuffer,
.txBufferSize = sizeof(lpuart1TxBuffer),
.rxBufferSize = sizeof(lpuart1RxBuffer),
.txBuffer = uartLp1TxBuffer,
.rxBuffer = uartLp1RxBuffer,
.txBufferSize = sizeof(uartLp1TxBuffer),
.rxBufferSize = sizeof(uartLp1RxBuffer),
},
#endif
};
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartPort_t *s = &(uartdev->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
s->checkUsartTxOutput = checkUsartTxOutput;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
uartdev->txPinState = TX_PIN_IGNORE;
if ((options & SERIAL_BIDIR) && txIO) {
ioConfig_t ioCfg = IO_CONFIG(
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PULLDOWN : GPIO_PULLUP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
} else {
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
}
}
#ifdef USE_DMA
if (!s->rxDMAResource)
#endif
{
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->rxIrq);
}
return s;
}
#endif // USE_UART

View file

@ -38,12 +38,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -51,8 +45,6 @@
#define USE_UART5
#define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6)
#define USE_INVERTER
#define USE_SPI_DEVICE_1

View file

@ -34,18 +34,10 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3)
#define USE_INVERTER
#define USE_SPI_DEVICE_1

View file

@ -35,18 +35,10 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
// #define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 2)
#define USE_INVERTER
#define USE_SPI_DEVICE_1

View file

@ -39,12 +39,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -54,8 +48,6 @@
#define USE_UART7
#define USE_UART8
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8)
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3

View file

@ -34,12 +34,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -47,8 +41,6 @@
#define USE_UART5
#define USE_UART6
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6)
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3

View file

@ -35,12 +35,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -48,8 +42,6 @@
#define USE_UART5
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 6)
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3

View file

@ -101,8 +101,6 @@
//#define USE_UART7
//#define USE_UART8
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 1)
//#define USE_SPI_DEVICE_1
//#define USE_SPI_DEVICE_2
//#define USE_SPI_DEVICE_3

View file

@ -54,12 +54,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -71,8 +65,6 @@
#define USE_UART9
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 10)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -63,8 +63,6 @@
#define USE_UART9
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 10)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
@ -83,12 +81,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_USB_DETECT
#define USE_ESCSERIAL

View file

@ -68,8 +68,6 @@
#define USE_VCP
#define UNIFIED_SERIAL_PORT_COUNT 1
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -82,8 +80,6 @@
#define USE_UART10
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 11)
// Disable OCTOSPI pins PB2/CLK, PB6/NCS, PD11/IO0, PD12/IO1, PD13/IO3, PE2/IO2
// PE7/IO4, PE8/IO5, PE9/IO6, PE10/IO7

View file

@ -35,12 +35,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -51,8 +45,6 @@
#define USE_UART8
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 9)
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3

View file

@ -68,12 +68,6 @@
#define USE_VCP
#ifdef USE_SOFTSERIAL
#define UNIFIED_SERIAL_PORT_COUNT 3
#else
#define UNIFIED_SERIAL_PORT_COUNT 1
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
@ -84,8 +78,6 @@
#define USE_UART8
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 9)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -117,9 +117,11 @@ cli_unittest_SRC := \
$(USER_DIR)/common/gps_conversion.c \
$(USER_DIR)/config/feature.c \
$(USER_DIR)/io/gps.c \
$(USER_DIR)/io/serial_resource.c \
$(USER_DIR)/pg/pg.c \
$(USER_DIR)/fc/runtime_config.c \
$(USER_DIR)/drivers/serial.c \
$(USER_DIR)/drivers/serial_impl.c \
$(USER_DIR)/common/typeconversion.c
cli_unittest_DEFINES := \
@ -175,6 +177,7 @@ gps_conversion_unittest_SRC := \
io_serial_unittest_SRC := \
$(USER_DIR)/io/serial.c \
$(USER_DIR)/io/serial_resource.c \
$(USER_DIR)/drivers/serial_pinconfig.c
@ -232,6 +235,7 @@ link_quality_unittest_SRC := \
$(USER_DIR)/common/vector.c \
$(USER_DIR)/drivers/display.c \
$(USER_DIR)/drivers/serial.c \
$(USER_DIR)/drivers/serial_impl.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/fc/runtime_config.c \
$(USER_DIR)/pg/pg.c \
@ -267,7 +271,9 @@ rx_crsf_unittest_SRC := \
$(USER_DIR)/common/printf.c \
$(USER_DIR)/common/typeconversion.c \
$(USER_DIR)/common/streambuf.c \
$(USER_DIR)/drivers/serial.c
$(USER_DIR)/drivers/serial.c \
$(USER_DIR)/drivers/serial_impl.c
rx_ibus_unittest_SRC := \
@ -347,6 +353,7 @@ telemetry_crsf_msp_unittest_SRC := \
$(USER_DIR)/common/printf.c \
$(USER_DIR)/common/streambuf.c \
$(USER_DIR)/drivers/serial.c \
$(USER_DIR)/drivers/serial_impl.c \
$(USER_DIR)/common/typeconversion.c \
$(USER_DIR)/telemetry/crsf.c \
$(USER_DIR)/common/gps_conversion.c \
@ -359,6 +366,7 @@ telemetry_crsf_msp_unittest_DEFINES := \
telemetry_hott_unittest_SRC := \
$(USER_DIR)/telemetry/hott.c \
$(USER_DIR)/io/serial_resource.c \
$(USER_DIR)/common/gps_conversion.c

View file

@ -70,11 +70,11 @@ extern "C" {
serialPort_t *usbVcpOpen(void) { return NULL; }
serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
serialPort_t *uartOpen(serialPortIdentifier_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
return NULL;
}
serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
serialPort_t *softSerialOpen(serialPortIdentifier_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
return NULL;
}

View file

@ -66,7 +66,6 @@
#define USE_UART5
#define USE_SOFTSERIAL
#define SERIAL_PORT_COUNT 8
#define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
#define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 6 // needed for unittest
@ -79,3 +78,4 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#include "target/serial_post.h"

View file

@ -0,0 +1,94 @@
from jinja2 import Environment, FileSystemLoader
import jinja2
import os
from datetime import datetime
import pprint
# generate normalization preprocessor file for serial ports
# configuration for template generation
serials = {
"UART": {"ids": [i + 1 for i in range(10)],
"inverter": True,
},
"LPUART": {"ids": [1],
"depends": {"UART"},
# "inverter": True, # TODO: old code compatibility only, disabled
},
"SOFTSERIAL": {"ids": [i + 1 for i in range(2)],
"use_enables_all": True,
"force_continuous": True,
},
"VCP": {"singleton": True,
"no_pins": True}
}
def flatten_config(data):
flattened_list = []
for key, value in data.items():
flattened_dict = {'typ': key}
# Update this new dictionary with the inner dictionary's items
flattened_dict.update(value)
flattened_list.append(flattened_dict)
return flattened_list
def pprint_filter(value, indent=4):
return pprint.pformat(value, indent=indent)
def rdepends_filter(cfg, typ):
return list(set([ c['typ'] for c in cfg if typ in c['depends'] ]))
def main():
# Setup Jinja2 environment
current_dir = os.path.dirname(os.path.abspath(__file__))
# Set the template directory relative to the current script
template_dir = os.path.join(current_dir, 'templates')
env = Environment(loader=FileSystemLoader(template_dir),
autoescape=True,
undefined=jinja2.StrictUndefined, # Throws an error on undefined variables
trim_blocks = True,
)
env.filters['pprint'] = pprint_filter
env.filters['zip'] = zip
env.filters['rdepends'] = rdepends_filter
template = env.get_template('serial_post.h')
# Read license file
license_path = 'DEFAULT_LICENSE.md'
with open(license_path, 'r') as file:
t_license = file.read()
context = {}
context['license'] = t_license
context['date_generated'] = datetime.now().strftime('%Y-%m-%d')
context['user_config'] = serials
config = flatten_config(serials)
context['config'] = config
for cfg in config:
singleton = cfg.setdefault('singleton', False)
no_pins = cfg.setdefault('no_pins', False)
inverter = cfg.setdefault('inverter', False)
cfg.setdefault("use_enables_all", False)
cfg.setdefault("force_continuous", False)
cfg.setdefault("depends", {})
typ = cfg['typ']
if singleton:
cfg['ports']= [ f"{typ}" ]
else:
cfg['ports'] = [ f"{typ}{i}" for i in cfg["ids"] ]
# Render the template with the license content
output = template.render(**context)
if False:
# Output or save to a file
output_path = './src/main/target/serial_post.h'
with open(output_path, 'w') as file:
file.write(output)
print(f"Generated file saved to {output_path}")
else:
print(output)
if __name__ == '__main__':
main()

View file

@ -0,0 +1,118 @@
{# serial_post.h #}
{# DEFAULT_LICENCE.md is used #}
{{ license|safe }}
/*
{# Start with generated warning. It you want to change something, edit this file #}
This file is automatically generated by src/utils/gen-serial.py script from src/utils/templates/serial_post.h jinja2 template.
Do not modify this file directly, your changes will be eventually lost.
See template{# THIS #} file for aditional documentation.
To generate this file again, run
> python ./src/utils/gen-serial-j2.py > ./src/main/target/serial_post.h
in Betaflight topmost directory.
This include will provide following defines:
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
All <type><n>_(RX|TX)_PINS are normalized too:
- if port is enabled, both will be defined (possibly as NONE)
- if port is not enable, both will be undefined, possibly with warning
- pass -DWARN_UNUSED_SERIAL_PORT to compiler to check pin defined without corresponding port being enabled.
{# add some usefull info #}
Generated on {{ date_generated }}
Configuration used:
{# TODO - maybe store configuration in this file, not Python one #}
{# TODO - pretty is not enough pretty #}
{{ user_config|pprint|safe }}
*/
#include "common/utils.h" // BIT, LOG2
{# config array is passed to this script. It is flattened version of user_config, with default fileld in #}
{% for cfg in config %}
/**** {{ cfg.typ }} *****/
{# use_enables_all - USE_<type> enables all ports of this type #}
{% if cfg.use_enables_all %}
#if defined(USE_{{cfg.typ}})
{% for port in cfg.ports %}
# if !defined(USE_{{port}})
# define USE_{{port}}
# endif
{% endfor %}
#endif
{% endif %}
{# USE_<port> - SERIAL_<port>_USED 0/1 #}
{% for port in cfg.ports %}
#if defined(USE_{{port}})
# define SERIAL_{{port}}_USED 1
#else
# define SERIAL_{{port}}_USED 0
#endif
{% endfor %}
{# SERIAL_<port>_* summary macros #}
{% if not cfg.singleton %}
{% set pipe = joiner(' | ') %}
#define SERIAL_{{ cfg.typ }}_MASK ({% for port, i in cfg.ports|zip(cfg.ids) %}{{ pipe() }}(SERIAL_{{ port }}_USED * BIT({{ i }} - 1)){% endfor %})
{% else %}
{# one port without number is defined #}
// set one bit if port is enabled for consistency
#define SERIAL_{{ cfg.typ }}_MASK (SERIAL_{{ cfg.ports[0] }}_USED * BIT(0))
{% endif %}
{% set plus = joiner(' + ') %}
#define SERIAL_{{ cfg.typ }}_COUNT ({% for port in cfg.ports %}{{ plus() }}SERIAL_{{ port }}_USED{% endfor %})
{# LOG2 is simpler than chaining MAX(SERIAL_x1_USED * 1, MAX(SERIAL_x2_USED * 2, ... #}
// 0 if no port is defined
#define SERIAL_{{ cfg.typ }}_MAX (SERIAL_{{cfg.typ}}_MASK ? LOG2(SERIAL_{{cfg.typ}}_MASK) + 1 : 0)
{# for softserial, we don't want softserial2 only #}
{% if cfg.force_continuous %}
#if SERIAL_{{cfg.typ}}_COUNT != SERIAL_{{cfg.typ}}_MAX
# error {{cfg.typ}} ports must start with {{cfg.typ}}1 and be continuous
#endif
{% endif %}
{# backward compatibility, code did set USE_INVERTER this way. It must be done before normalizing to NONE #}
{% if cfg.inverter %}
// enable USE_INVERTED first, before normalization
{% set pipe2 = joiner(' || ') %}
#if !defined(USE_INVERTER) && ({% for port in cfg.ports %}{{ pipe2() }}INVERTER_PIN_{{ port }}{% endfor %})
# define USE_INVERTER
#endif
{% endif %}
{# no pins for VCP port #}
{% if not cfg.no_pins %}
// Normalize {{cfg.typ}} TX/RX{{ "/INVERTER" if cfg.inverter else "" }}
{% for port in cfg.ports %}
{% set pins = [ port ~ '_RX_PIN', port ~ '_TX_PIN' ] + (['INVERTER_PIN_' ~ port] if cfg.inverter else []) %}
{% for pin in pins %}
#if SERIAL_{{port}}_USED && !defined({{pin}})
# define {{ pin }} NONE
#endif
#if defined(WARN_UNUSED_SERIAL_PORT) && !SERIAL_{{ port }}_USED && defined({{ pin }})
# warning "{{ pin }} is defined but {{ port }} is not enabled"
#endif
#if !SERIAL_{{ port }}_USED && defined({{ pin }})
# undef {{ pin }}
#endif
{% endfor %}
{% endfor %}
{% endif %}
{% endfor %}
// normalize USE_x after all ports are enumerated (x_COUNT of dependencies must be available)
{% for cfg in config %}
{% set depends = [cfg.typ] + config|rdepends(cfg.typ) %}
{% set pipe2 = joiner(' || ') %}
#if !defined(USE_{{cfg.typ}}) && ({% for typ in depends %}{{ pipe2() }}SERIAL_{{ typ }}_COUNT{% endfor %})
# define USE_{{cfg.typ}}
#endif
{% endfor %}