Adding support for UART0 (#14094)
[betaflight.git] / src / main / io / serial.c
bloba97d8260a547476e621a892d7c37c467bfb1731c
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
25 #include "platform.h"
27 #include "build/build_config.h"
29 #include "cli/cli.h"
31 #include "common/maths.h"
32 #include "common/utils.h"
34 #include "drivers/time.h"
35 #include "drivers/system.h"
36 #include "drivers/serial.h"
37 #include "drivers/serial_uart.h"
38 #if defined(USE_SOFTSERIAL)
39 #include "drivers/serial_softserial.h"
40 #endif
42 #if defined(SIMULATOR_BUILD)
43 #include "drivers/serial_tcp.h"
44 #endif
46 #include "drivers/light_led.h"
48 #if defined(USE_VCP)
49 #include "drivers/serial_usb_vcp.h"
50 #endif
52 #include "config/config.h"
54 #include "io/serial.h"
56 #include "msp/msp_serial.h"
58 #include "pg/pg.h"
59 #include "pg/pg_ids.h"
61 #ifdef USE_TELEMETRY
62 #include "telemetry/telemetry.h"
63 #endif
65 #include "pg/pinio.h"
67 static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
69 const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
70 #ifdef USE_VCP
71 SERIAL_PORT_USB_VCP,
72 #endif
73 #ifdef USE_UART0
74 SERIAL_PORT_UART0,
75 #endif
76 #ifdef USE_UART1
77 SERIAL_PORT_USART1,
78 #endif
79 #ifdef USE_UART2
80 SERIAL_PORT_USART2,
81 #endif
82 #ifdef USE_UART3
83 SERIAL_PORT_USART3,
84 #endif
85 #ifdef USE_UART4
86 SERIAL_PORT_UART4,
87 #endif
88 #ifdef USE_UART5
89 SERIAL_PORT_UART5,
90 #endif
91 #ifdef USE_UART6
92 SERIAL_PORT_USART6,
93 #endif
94 #ifdef USE_UART7
95 SERIAL_PORT_USART7,
96 #endif
97 #ifdef USE_UART8
98 SERIAL_PORT_USART8,
99 #endif
100 #ifdef USE_UART9
101 SERIAL_PORT_UART9,
102 #endif
103 #ifdef USE_UART10
104 SERIAL_PORT_USART10,
105 #endif
106 #ifdef USE_SOFTSERIAL1
107 SERIAL_PORT_SOFTSERIAL1,
108 #endif
109 #ifdef USE_SOFTSERIAL2
110 SERIAL_PORT_SOFTSERIAL2,
111 #endif
112 #ifdef USE_LPUART1
113 SERIAL_PORT_LPUART1,
114 #endif
117 const char* serialPortNames[SERIAL_PORT_COUNT] = {
118 #ifdef USE_VCP
119 "VCP",
120 #endif
121 #ifdef USE_UART0
122 "UART0",
123 #endif
124 #ifdef USE_UART1
125 "UART1",
126 #endif
127 #ifdef USE_UART2
128 "UART2",
129 #endif
130 #ifdef USE_UART3
131 "UART3",
132 #endif
133 #ifdef USE_UART4
134 "UART4",
135 #endif
136 #ifdef USE_UART5
137 "UART5",
138 #endif
139 #ifdef USE_UART6
140 "UART6",
141 #endif
142 #ifdef USE_UART7
143 "UART7",
144 #endif
145 #ifdef USE_UART8
146 "UART8",
147 #endif
148 #ifdef USE_UART9
149 "UART9",
150 #endif
151 #ifdef USE_UART10
152 "UART10",
153 #endif
154 #ifdef USE_SOFTSERIAL1
155 "SOFT1",
156 #endif
157 #ifdef USE_SOFTSERIAL2
158 "SOFT2",
159 #endif
160 #ifdef USE_LPUART1
161 "LPUART1",
162 #endif
165 const uint32_t baudRates[BAUD_COUNT] = {
166 0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
167 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000
168 }; // see baudRate_e
170 static serialPortConfig_t* findInPortConfigs_identifier(const serialPortConfig_t cfgs[], size_t count, serialPortIdentifier_e identifier)
172 if (identifier == SERIAL_PORT_NONE || identifier == SERIAL_PORT_ALL) {
173 return NULL;
176 for (unsigned i = 0; i < count; i++) {
177 if (cfgs[i].identifier == identifier) {
178 // drop const on return - wrapper function will add it back if necessary
179 return (serialPortConfig_t*)&cfgs[i];
183 return NULL;
186 serialPortConfig_t* serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
188 return findInPortConfigs_identifier(serialConfigMutable()->portConfigs, ARRAYLEN(serialConfigMutable()->portConfigs), identifier);
191 const serialPortConfig_t* serialFindPortConfiguration(serialPortIdentifier_e identifier)
193 return findInPortConfigs_identifier(serialConfig()->portConfigs, ARRAYLEN(serialConfig()->portConfigs), identifier);
196 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
198 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
200 memset(serialConfig, 0, sizeof(serialConfig_t));
202 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
203 serialPortConfig_t* pCfg = &serialConfig->portConfigs[i];
204 pCfg->identifier = serialPortIdentifiers[i];
205 pCfg->msp_baudrateIndex = BAUD_115200;
206 pCfg->gps_baudrateIndex = BAUD_57600;
207 pCfg->telemetry_baudrateIndex = BAUD_AUTO;
208 pCfg->blackbox_baudrateIndex = BAUD_115200;
211 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
213 #ifdef MSP_UART
214 serialPortConfig_t *uart2Config = serialFindPortConfigurationMutable(MSP_UART);
215 if (uart2Config) {
216 uart2Config->functionMask = FUNCTION_MSP;
218 #endif
220 #if defined(USE_GPS) && defined(GPS_UART)
221 serialPortConfig_t *gpsUartConfig = serialFindPortConfigurationMutable(GPS_UART);
222 if (gpsUartConfig) {
223 gpsUartConfig->functionMask = FUNCTION_GPS;
225 #endif
227 #ifdef SERIALRX_UART
228 serialPortConfig_t *serialRxUartConfig = serialFindPortConfigurationMutable(SERIALRX_UART);
229 if (serialRxUartConfig) {
230 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
232 #endif
234 #ifdef SBUS_TELEMETRY_UART
235 serialPortConfig_t *serialTelemetryUartConfig = serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART);
236 if (serialTelemetryUartConfig) {
237 serialTelemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
239 #endif
241 #ifdef ESC_SENSOR_UART
242 serialPortConfig_t *escSensorUartConfig = serialFindPortConfigurationMutable(ESC_SENSOR_UART);
243 if (escSensorUartConfig) {
244 escSensorUartConfig->functionMask = FUNCTION_ESC_SENSOR;
246 #endif
248 #ifdef USE_VTX
249 #ifdef VTX_SMARTAUDIO_UART
250 serialPortConfig_t *vtxSmartAudioUartConfig = serialFindPortConfigurationMutable(VTX_SMARTAUDIO_UART);
251 if (vtxSmartAudioUartConfig) {
252 vtxSmartAudioUartConfig->functionMask = FUNCTION_VTX_SMARTAUDIO;
254 #endif
256 #ifdef VTX_TRAMP_UART
257 serialPortConfig_t *vtxTrampUartConfig = serialFindPortConfigurationMutable(VTX_TRAMP_UART);
258 if (vtxTrampUartConfig) {
259 vtxTrampUartConfig->functionMask = FUNCTION_VTX_TRAMP;
261 #endif
263 #ifdef VTX_MSP_UART
264 serialPortConfig_t *vtxMspUartConfig = serialFindPortConfigurationMutable(VTX_MSP_UART);
265 if (vtxMspUartConfig) {
266 vtxMspUartConfig->functionMask = FUNCTION_VTX_MSP;
268 #endif
269 #endif // USE_VTX
271 #ifdef MSP_DISPLAYPORT_UART
272 serialPortConfig_t *displayPortUartConfig = serialFindPortConfigurationMutable(MSP_DISPLAYPORT_UART);
273 if (displayPortUartConfig) {
274 displayPortUartConfig->functionMask = FUNCTION_VTX_MSP | FUNCTION_MSP;
276 #endif
278 #if defined(USE_MSP_UART)
279 serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(USE_MSP_UART);
280 if (uart1Config) {
281 uart1Config->functionMask = FUNCTION_MSP;
283 #endif
285 serialConfig->reboot_character = 'R';
286 serialConfig->serial_update_rate_hz = 100;
289 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
291 for (unsigned index = 0; index < ARRAYLEN(baudRates); index++) {
292 if (baudRates[index] == baudRate) {
293 return index;
296 return BAUD_AUTO;
299 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
301 for (unsigned index = 0; index < ARRAYLEN(serialPortIdentifiers); index++) {
302 if (serialPortIdentifiers[index] == identifier) {
303 return index;
306 return -1;
309 // find serial port by name.
310 // when cmp is NULL, case-insensitive compare is used
311 // cmp is strcmp-like function
312 serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(const char *portName, const char *candidate))
314 if (!cmp) { // use strcasecmp by default
315 cmp = strcasecmp;
317 for (unsigned i = 0; i < ARRAYLEN(serialPortNames); i++) {
318 if (cmp(portName, serialPortNames[i]) == 0) {
319 return serialPortIdentifiers[i]; // 1:1 map between names and identifiers
322 return SERIAL_PORT_NONE;
325 const char* serialName(serialPortIdentifier_e identifier, const char* notFound)
327 const int idx = findSerialPortIndexByIdentifier(identifier);
328 return idx >= 0 ? serialPortNames[idx] : notFound;
331 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
333 for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) {
334 if (usage->identifier == identifier) {
335 return usage;
338 return NULL;
341 serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort)
343 for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) {
344 if (usage->serialPort == serialPort) {
345 return usage;
348 return NULL;
351 typedef struct findSerialPortConfigState_s {
352 uint8_t lastIndex;
353 } findSerialPortConfigState_t;
355 static findSerialPortConfigState_t findSerialPortConfigState;
357 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
359 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
361 return findNextSerialPortConfig(function);
364 const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
366 while (findSerialPortConfigState.lastIndex < ARRAYLEN(serialConfig()->portConfigs)) {
367 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
369 if (candidate->functionMask & function) {
370 return candidate;
373 return NULL;
376 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
378 if (!portConfig || (portConfig->functionMask & function) == 0) {
379 return PORTSHARING_UNUSED;
381 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
384 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
386 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
389 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
391 for (const serialPortConfig_t *candidate = serialConfig()->portConfigs;
392 candidate < ARRAYEND(serialConfig()->portConfigs);
393 candidate++) {
394 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
395 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
396 if (!serialPortUsage) {
397 continue;
399 return serialPortUsage->serialPort;
402 return NULL;
405 #ifdef USE_TELEMETRY
406 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP)
407 #else
408 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP)
409 #endif
411 bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
414 * rules:
415 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
416 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
417 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
418 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
419 * (serial RX using RX line, telemetry using TX line)
420 * - No other sharing combinations are valid.
422 uint8_t mspPortCount = 0;
424 for (unsigned index = 0; index < ARRAYLEN(serialConfigToCheck->portConfigs); index++) {
425 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
427 #ifdef USE_SOFTSERIAL
428 if (serialType(portConfig->identifier) == SERIALTYPE_SOFTSERIAL) {
429 // Ensure MSP or serial RX is not enabled on soft serial ports
430 serialConfigToCheck->portConfigs[index].functionMask &= ~(FUNCTION_MSP | FUNCTION_RX_SERIAL);
431 // Ensure that the baud rate on soft serial ports is limited to 19200
432 #ifndef USE_OVERRIDE_SOFTSERIAL_BAUDRATE
433 serialConfigToCheck->portConfigs[index].gps_baudrateIndex = constrain(portConfig->gps_baudrateIndex, BAUD_AUTO, BAUD_19200);
434 serialConfigToCheck->portConfigs[index].blackbox_baudrateIndex = constrain(portConfig->blackbox_baudrateIndex, BAUD_AUTO, BAUD_19200);
435 serialConfigToCheck->portConfigs[index].telemetry_baudrateIndex = constrain(portConfig->telemetry_baudrateIndex, BAUD_AUTO, BAUD_19200);
436 #endif
438 #endif // USE_SOFTSERIAL
440 if (portConfig->functionMask & FUNCTION_MSP) {
441 mspPortCount++;
443 if (portConfig->identifier == SERIAL_PORT_USB_VCP
444 && (portConfig->functionMask & FUNCTION_MSP) == 0) {
445 // Require MSP to be enabled for the VCP port
446 return false;
449 uint8_t bitCount = popcount32(portConfig->functionMask);
451 #ifdef USE_VTX_MSP
452 if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
453 return false;
455 #endif
457 if (bitCount > 1) {
458 // shared
459 if (bitCount > (BITCOUNT(FUNCTION_MSP | ALL_FUNCTIONS_SHARABLE_WITH_MSP))) {
460 return false;
463 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
464 // MSP & telemetry
465 #ifdef USE_TELEMETRY
466 } else if (telemetryCheckRxPortShared(portConfig, rxConfig()->serialrx_provider)) {
467 // serial RX & telemetry
468 #endif
469 } else {
470 // some other combination
471 return false;
476 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
477 return false;
479 return true;
482 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
484 const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
485 return candidate != NULL && candidate->functionMask;
488 serialPort_t *openSerialPort(
489 serialPortIdentifier_e identifier,
490 serialPortFunction_e function,
491 serialReceiveCallbackPtr rxCallback,
492 void *rxCallbackData,
493 uint32_t baudRate,
494 portMode_e mode,
495 portOptions_e options)
497 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL) || defined(USE_LPUART))
498 UNUSED(rxCallback);
499 UNUSED(rxCallbackData);
500 UNUSED(baudRate);
501 UNUSED(mode);
502 UNUSED(options);
503 #endif
505 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
506 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
507 // not available / already in use
508 return NULL;
511 serialPort_t *serialPort = NULL;
513 switch (serialType(identifier)) {
514 #if defined(USE_VCP)
515 case SERIALTYPE_USB_VCP:
516 serialPort = usbVcpOpen();
517 break;
518 #endif
519 #if defined(USE_UART)
520 case SERIALTYPE_UART:
521 case SERIALTYPE_LPUART:
522 #if defined(SIMULATOR_BUILD)
523 // emulate serial ports over TCP
524 serialPort = serTcpOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
525 #else
526 serialPort = uartOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
527 #endif
528 #endif
529 break;
530 #ifdef USE_SOFTSERIAL
531 case SERIALTYPE_SOFTSERIAL:
532 # if !defined(USE_OVERRIDE_SOFTSERIAL_BAUDRATE)
533 if (baudRate > 19200) {
534 // Don't continue if baud rate requested is higher then the limit set on soft serial ports
535 return NULL;
537 # endif // !USE_OVERRIDE_SOFTSERIAL_BAUDRATE
538 serialPort = softSerialOpen(identifier, rxCallback, rxCallbackData, baudRate, mode, options);
539 break;
540 #endif // USE_SOFTSERIAL
541 default:
542 break;
545 if (!serialPort) {
546 return NULL;
549 serialPort->identifier = identifier; // Some versions of *Open() set this member sooner
551 serialPortUsage->function = function;
552 serialPortUsage->serialPort = serialPort;
554 return serialPort;
557 void closeSerialPort(serialPort_t *serialPort)
559 if (!serialPort) {
560 return;
562 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
563 if (!serialPortUsage) {
564 // already closed
565 return;
568 // TODO wait until data has been transmitted.
569 serialPort->rxCallback = NULL;
571 serialPortUsage->function = FUNCTION_NONE;
572 serialPortUsage->serialPort = NULL;
575 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
577 #if !defined(USE_SOFTSERIAL)
578 UNUSED(softserialEnabled);
579 #endif
581 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
583 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
584 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
586 if (serialPortToDisable != SERIAL_PORT_NONE
587 && serialPortUsageList[index].identifier == serialPortToDisable) {
588 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
589 continue; // this index is deleted
592 #if !defined(SIMULATOR_BUILD) // no serialPinConfig on SITL
593 const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier);
594 if (resourceIndex >= 0 // resource exists
595 && !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
596 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
597 continue;
599 #endif
601 if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL) {
602 if (true
603 #ifdef USE_SOFTSERIAL
604 && !softserialEnabled
605 #endif
607 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
608 continue;
614 void serialRemovePort(serialPortIdentifier_e identifier)
616 serialPortUsage_t* usage;
617 while ((usage = findSerialPortUsageByIdentifier(identifier)) != NULL) {
618 usage->identifier = SERIAL_PORT_NONE;
622 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
624 return findSerialPortUsageByIdentifier(identifier) != NULL;
627 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
629 while (!isSerialTransmitBufferEmpty(serialPort)) {
630 delay(10);
634 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
635 // Default data consumer for serialPassThrough.
636 static void nopConsumer(uint8_t data)
638 UNUSED(data);
642 A high-level serial passthrough implementation. Used by cli to start an
643 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
644 for specialized data processing.
646 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
648 waitForSerialPortToFinishTransmitting(left);
649 waitForSerialPortToFinishTransmitting(right);
651 if (!leftC)
652 leftC = &nopConsumer;
653 if (!rightC)
654 rightC = &nopConsumer;
656 LED0_OFF;
657 LED1_OFF;
659 // Either port might be open in a mode other than MODE_RXTX. We rely on
660 // serialRxBytesWaiting() to do the right thing for a TX only port. No
661 // special handling is necessary OR performed.
662 while (1) {
663 // TODO: maintain a timestamp of last data received. Use this to
664 // implement a guard interval and check for `+++` as an escape sequence
665 // to return to CLI command mode.
666 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
667 if (serialRxBytesWaiting(left)) {
668 LED0_ON;
669 uint8_t c = serialRead(left);
670 // Make sure there is space in the tx buffer
671 while (!serialTxBytesFree(right));
672 serialWrite(right, c);
673 leftC(c);
674 LED0_OFF;
676 if (serialRxBytesWaiting(right)) {
677 LED0_ON;
678 uint8_t c = serialRead(right);
679 // Make sure there is space in the tx buffer
680 while (!serialTxBytesFree(left));
681 serialWrite(left, c);
682 rightC(c);
683 LED0_OFF;
687 #endif