Dshot RPM Telemetry Refactoring (#13012)
[betaflight.git] / src / main / io / serial.c
blob4ed8a98b09992d8fe10c911ac303f0e8921455a7
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/utils.h"
33 #include "drivers/time.h"
34 #include "drivers/system.h"
35 #include "drivers/serial.h"
36 #include "drivers/serial_uart.h"
37 #if defined(USE_SOFTSERIAL)
38 #include "drivers/serial_softserial.h"
39 #endif
41 #if defined(SIMULATOR_BUILD)
42 #include "drivers/serial_tcp.h"
43 #endif
45 #include "drivers/light_led.h"
47 #if defined(USE_VCP)
48 #include "drivers/serial_usb_vcp.h"
49 #endif
51 #include "config/config.h"
53 #include "io/serial.h"
55 #include "msp/msp_serial.h"
57 #include "pg/pg.h"
58 #include "pg/pg_ids.h"
60 #ifdef USE_TELEMETRY
61 #include "telemetry/telemetry.h"
62 #endif
64 #include "pg/pinio.h"
66 static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
68 const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
69 #ifdef USE_VCP
70 SERIAL_PORT_USB_VCP,
71 #endif
72 #ifdef USE_UART1
73 SERIAL_PORT_USART1,
74 #endif
75 #ifdef USE_UART2
76 SERIAL_PORT_USART2,
77 #endif
78 #ifdef USE_UART3
79 SERIAL_PORT_USART3,
80 #endif
81 #ifdef USE_UART4
82 SERIAL_PORT_UART4,
83 #endif
84 #ifdef USE_UART5
85 SERIAL_PORT_UART5,
86 #endif
87 #ifdef USE_UART6
88 SERIAL_PORT_USART6,
89 #endif
90 #ifdef USE_UART7
91 SERIAL_PORT_USART7,
92 #endif
93 #ifdef USE_UART8
94 SERIAL_PORT_USART8,
95 #endif
96 #ifdef USE_UART9
97 SERIAL_PORT_UART9,
98 #endif
99 #ifdef USE_UART10
100 SERIAL_PORT_USART10,
101 #endif
102 #ifdef USE_SOFTSERIAL
103 SERIAL_PORT_SOFTSERIAL1,
104 SERIAL_PORT_SOFTSERIAL2,
105 #endif
106 #ifdef USE_LPUART1
107 SERIAL_PORT_LPUART1,
108 #endif
111 static uint8_t serialPortCount;
113 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
114 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
116 #define BAUD_RATE_COUNT ARRAYLEN(baudRates)
118 serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
120 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
121 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
122 if (candidate->identifier == identifier) {
123 return candidate;
126 return NULL;
129 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
131 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
133 memset(serialConfig, 0, sizeof(serialConfig_t));
135 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
136 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
137 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
138 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_57600;
139 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
140 serialConfig->portConfigs[i].blackbox_baudrateIndex = BAUD_115200;
143 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
145 #ifdef MSP_UART
146 serialPortConfig_t *uart2Config = serialFindPortConfigurationMutable(MSP_UART);
147 if (uart2Config) {
148 uart2Config->functionMask = FUNCTION_MSP;
150 #endif
152 #if defined(USE_GPS) && defined(GPS_UART)
153 serialPortConfig_t *gpsUartConfig = serialFindPortConfigurationMutable(GPS_UART);
154 if (gpsUartConfig) {
155 gpsUartConfig->functionMask = FUNCTION_GPS;
157 #endif
159 #ifdef SERIALRX_UART
160 serialPortConfig_t *serialRxUartConfig = serialFindPortConfigurationMutable(SERIALRX_UART);
161 if (serialRxUartConfig) {
162 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
164 #endif
166 #ifdef SBUS_TELEMETRY_UART
167 serialPortConfig_t *serialTelemetryUartConfig = serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART);
168 if (serialTelemetryUartConfig) {
169 serialTelemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
171 #endif
173 #ifdef ESC_SENSOR_UART
174 serialPortConfig_t *escSensorUartConfig = serialFindPortConfigurationMutable(ESC_SENSOR_UART);
175 if (escSensorUartConfig) {
176 escSensorUartConfig->functionMask = FUNCTION_ESC_SENSOR;
178 #endif
180 #ifdef USE_VTX
181 #ifdef VTX_SMARTAUDIO_UART
182 serialPortConfig_t *vtxSmartAudioUartConfig = serialFindPortConfigurationMutable(VTX_SMARTAUDIO_UART);
183 if (vtxSmartAudioUartConfig) {
184 vtxSmartAudioUartConfig->functionMask = FUNCTION_VTX_SMARTAUDIO;
186 #endif
188 #ifdef VTX_TRAMP_UART
189 serialPortConfig_t *vtxTrampUartConfig = serialFindPortConfigurationMutable(VTX_TRAMP_UART);
190 if (vtxTrampUartConfig) {
191 vtxTrampUartConfig->functionMask = FUNCTION_VTX_TRAMP;
193 #endif
195 #ifdef VTX_MSP_UART
196 serialPortConfig_t *vtxMspUartConfig = serialFindPortConfigurationMutable(VTX_MSP_UART);
197 if (vtxMspUartConfig) {
198 vtxMspUartConfig->functionMask = FUNCTION_VTX_MSP;
200 #endif
201 #endif // USE_VTX
203 #ifdef MSP_DISPLAYPORT_UART
204 serialPortConfig_t *displayPortUartConfig = serialFindPortConfigurationMutable(MSP_DISPLAYPORT_UART);
205 if (displayPortUartConfig) {
206 displayPortUartConfig->functionMask = FUNCTION_VTX_MSP | FUNCTION_MSP;
208 #endif
210 #if defined(USE_MSP_UART)
211 serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(USE_MSP_UART);
212 if (uart1Config) {
213 uart1Config->functionMask = FUNCTION_MSP;
215 #endif
217 serialConfig->reboot_character = 'R';
218 serialConfig->serial_update_rate_hz = 100;
221 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
223 uint8_t index;
225 for (index = 0; index < BAUD_RATE_COUNT; index++) {
226 if (baudRates[index] == baudRate) {
227 return index;
230 return BAUD_AUTO;
233 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
235 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
236 if (serialPortIdentifiers[index] == identifier) {
237 return index;
240 return -1;
243 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
245 uint8_t index;
246 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
247 serialPortUsage_t *candidate = &serialPortUsageList[index];
248 if (candidate->identifier == identifier) {
249 return candidate;
252 return NULL;
255 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort)
257 uint8_t index;
258 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
259 serialPortUsage_t *candidate = &serialPortUsageList[index];
260 if (candidate->serialPort == serialPort) {
261 return candidate;
264 return NULL;
267 typedef struct findSerialPortConfigState_s {
268 uint8_t lastIndex;
269 } findSerialPortConfigState_t;
271 static findSerialPortConfigState_t findSerialPortConfigState;
273 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
275 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
277 return findNextSerialPortConfig(function);
280 const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
282 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
283 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
285 if (candidate->functionMask & function) {
286 return candidate;
289 return NULL;
292 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
294 if (!portConfig || (portConfig->functionMask & function) == 0) {
295 return PORTSHARING_UNUSED;
297 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
300 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
302 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
305 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
307 for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
308 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
310 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
311 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
312 if (!serialPortUsage) {
313 continue;
315 return serialPortUsage->serialPort;
318 return NULL;
321 #ifdef USE_TELEMETRY
322 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP)
323 #else
324 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP)
325 #endif
327 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
329 UNUSED(serialConfigToCheck);
331 * rules:
332 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
333 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
334 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
335 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
336 * (serial RX using RX line, telemetry using TX line)
337 * - No other sharing combinations are valid.
339 uint8_t mspPortCount = 0;
341 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
342 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
344 if (portConfig->functionMask & FUNCTION_MSP) {
345 mspPortCount++;
346 } else if (portConfig->identifier == SERIAL_PORT_USB_VCP) {
347 // Require MSP to be enabled for the VCP port
348 return false;
351 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
353 #ifdef USE_VTX_MSP
354 if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
355 return false;
357 #endif
359 if (bitCount > 1) {
360 // shared
361 if (bitCount > (BITCOUNT(FUNCTION_MSP | ALL_FUNCTIONS_SHARABLE_WITH_MSP))) {
362 return false;
365 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
366 // MSP & telemetry
367 #ifdef USE_TELEMETRY
368 } else if (telemetryCheckRxPortShared(portConfig, rxConfig()->serialrx_provider)) {
369 // serial RX & telemetry
370 #endif
371 } else {
372 // some other combination
373 return false;
378 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
379 return false;
381 return true;
384 const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
386 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
387 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index];
388 if (candidate->identifier == identifier) {
389 return candidate;
392 return NULL;
395 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
397 const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
398 return candidate != NULL && candidate->functionMask;
401 serialPort_t *openSerialPort(
402 serialPortIdentifier_e identifier,
403 serialPortFunction_e function,
404 serialReceiveCallbackPtr rxCallback,
405 void *rxCallbackData,
406 uint32_t baudRate,
407 portMode_e mode,
408 portOptions_e options)
410 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL))
411 UNUSED(rxCallback);
412 UNUSED(rxCallbackData);
413 UNUSED(baudRate);
414 UNUSED(mode);
415 UNUSED(options);
416 #endif
418 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
419 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
420 // not available / already in use
421 return NULL;
424 serialPort_t *serialPort = NULL;
426 switch (identifier) {
427 #ifdef USE_VCP
428 case SERIAL_PORT_USB_VCP:
429 serialPort = usbVcpOpen();
430 break;
431 #endif
433 #if defined(USE_UART)
434 #ifdef USE_UART1
435 case SERIAL_PORT_USART1:
436 #endif
437 #ifdef USE_UART2
438 case SERIAL_PORT_USART2:
439 #endif
440 #ifdef USE_UART3
441 case SERIAL_PORT_USART3:
442 #endif
443 #ifdef USE_UART4
444 case SERIAL_PORT_UART4:
445 #endif
446 #ifdef USE_UART5
447 case SERIAL_PORT_UART5:
448 #endif
449 #ifdef USE_UART6
450 case SERIAL_PORT_USART6:
451 #endif
452 #ifdef USE_UART7
453 case SERIAL_PORT_USART7:
454 #endif
455 #ifdef USE_UART8
456 case SERIAL_PORT_USART8:
457 #endif
458 #ifdef USE_UART9
459 case SERIAL_PORT_UART9:
460 #endif
461 #ifdef USE_UART10
462 case SERIAL_PORT_USART10:
463 #endif
464 #ifdef USE_LPUART1
465 case SERIAL_PORT_LPUART1:
466 #endif
467 #if defined(SIMULATOR_BUILD)
468 // emulate serial ports over TCP
469 serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
470 #else
471 serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
472 #endif
473 break;
474 #endif
476 #ifdef USE_SOFTSERIAL
477 case SERIAL_PORT_SOFTSERIAL1:
478 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
479 break;
480 case SERIAL_PORT_SOFTSERIAL2:
481 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
482 break;
483 #endif
484 default:
485 break;
488 if (!serialPort) {
489 return NULL;
492 serialPort->identifier = identifier;
494 serialPortUsage->function = function;
495 serialPortUsage->serialPort = serialPort;
497 return serialPort;
500 void closeSerialPort(serialPort_t *serialPort)
502 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
503 if (!serialPortUsage) {
504 // already closed
505 return;
508 // TODO wait until data has been transmitted.
509 serialPort->rxCallback = NULL;
511 serialPortUsage->function = FUNCTION_NONE;
512 serialPortUsage->serialPort = NULL;
515 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
517 #if !defined(USE_SOFTSERIAL)
518 UNUSED(softserialEnabled);
519 #endif
521 serialPortCount = SERIAL_PORT_COUNT;
522 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
524 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
525 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
527 if (serialPortToDisable != SERIAL_PORT_NONE) {
528 if (serialPortUsageList[index].identifier == serialPortToDisable) {
529 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
530 serialPortCount--;
533 #if !defined(SIMULATOR_BUILD)
534 else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART10
535 #ifdef USE_LPUART1
536 || serialPortUsageList[index].identifier == SERIAL_PORT_LPUART1
537 #endif
539 int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
540 if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
541 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
542 serialPortCount--;
545 #endif
546 #ifdef USE_SOFTSERIAL
547 else if (((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1) &&
548 (!softserialEnabled || !(softSerialPinConfig()->ioTagRx[SOFTSERIAL1] || softSerialPinConfig()->ioTagTx[SOFTSERIAL1]))) ||
549 ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2) &&
550 (!softserialEnabled || !(softSerialPinConfig()->ioTagRx[SOFTSERIAL2] || softSerialPinConfig()->ioTagTx[SOFTSERIAL2]))))
551 #else
552 else if (
553 (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1) ||
554 (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2)
556 #endif
558 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
559 serialPortCount--;
564 void serialRemovePort(serialPortIdentifier_e identifier)
566 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
567 if (serialPortUsageList[index].identifier == identifier) {
568 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
569 serialPortCount--;
574 uint8_t serialGetAvailablePortCount(void)
576 return serialPortCount;
579 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
581 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
582 if (serialPortUsageList[index].identifier == identifier) {
583 return true;
586 return false;
589 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
591 while (!isSerialTransmitBufferEmpty(serialPort)) {
592 delay(10);
596 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
597 // Default data consumer for serialPassThrough.
598 static void nopConsumer(uint8_t data)
600 UNUSED(data);
604 A high-level serial passthrough implementation. Used by cli to start an
605 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
606 for specialized data processing.
608 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
610 waitForSerialPortToFinishTransmitting(left);
611 waitForSerialPortToFinishTransmitting(right);
613 if (!leftC)
614 leftC = &nopConsumer;
615 if (!rightC)
616 rightC = &nopConsumer;
618 LED0_OFF;
619 LED1_OFF;
621 // Either port might be open in a mode other than MODE_RXTX. We rely on
622 // serialRxBytesWaiting() to do the right thing for a TX only port. No
623 // special handling is necessary OR performed.
624 while (1) {
625 // TODO: maintain a timestamp of last data received. Use this to
626 // implement a guard interval and check for `+++` as an escape sequence
627 // to return to CLI command mode.
628 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
629 if (serialRxBytesWaiting(left)) {
630 LED0_ON;
631 uint8_t c = serialRead(left);
632 // Make sure there is space in the tx buffer
633 while (!serialTxBytesFree(right));
634 serialWrite(right, c);
635 leftC(c);
636 LED0_OFF;
638 if (serialRxBytesWaiting(right)) {
639 LED0_ON;
640 uint8_t c = serialRead(right);
641 // Make sure there is space in the tx buffer
642 while (!serialTxBytesFree(left));
643 serialWrite(left, c);
644 rightC(c);
645 LED0_OFF;
649 #endif