Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / io / serial.c
blob92d75971a0bdbbe1840222a9846fab8871ce1324
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_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
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_SOFTSERIAL1
103 SERIAL_PORT_SOFTSERIAL1,
104 #endif
105 #ifdef USE_SOFTSERIAL2
106 SERIAL_PORT_SOFTSERIAL2,
107 #endif
108 #ifdef USE_LPUART1
109 SERIAL_PORT_LPUART1
110 #endif
113 static uint8_t serialPortCount;
115 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
116 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
118 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
120 serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
122 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
123 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
124 if (candidate->identifier == identifier) {
125 return candidate;
128 return NULL;
131 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
133 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
135 memset(serialConfig, 0, sizeof(serialConfig_t));
137 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
138 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
139 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
140 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_57600;
141 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
142 serialConfig->portConfigs[i].blackbox_baudrateIndex = BAUD_115200;
145 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
147 #ifdef SERIALRX_UART
148 serialPortConfig_t *serialRxUartConfig = serialFindPortConfigurationMutable(SERIALRX_UART);
149 if (serialRxUartConfig) {
150 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
152 #endif
154 #ifdef SBUS_TELEMETRY_UART
155 serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART);
156 if (serialTlemetryUartConfig) {
157 serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
159 #endif
161 #if defined(USE_VCP) && defined(USE_MSP_UART)
162 if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
163 serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(SERIAL_PORT_USART1);
164 if (uart1Config) {
165 uart1Config->functionMask = FUNCTION_MSP;
168 #endif
170 serialConfig->reboot_character = 'R';
171 serialConfig->serial_update_rate_hz = 100;
174 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
176 uint8_t index;
178 for (index = 0; index < BAUD_RATE_COUNT; index++) {
179 if (baudRates[index] == baudRate) {
180 return index;
183 return BAUD_AUTO;
186 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
188 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
189 if (serialPortIdentifiers[index] == identifier) {
190 return index;
193 return -1;
196 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
198 uint8_t index;
199 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
200 serialPortUsage_t *candidate = &serialPortUsageList[index];
201 if (candidate->identifier == identifier) {
202 return candidate;
205 return NULL;
208 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
209 uint8_t index;
210 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
211 serialPortUsage_t *candidate = &serialPortUsageList[index];
212 if (candidate->serialPort == serialPort) {
213 return candidate;
216 return NULL;
219 typedef struct findSerialPortConfigState_s {
220 uint8_t lastIndex;
221 } findSerialPortConfigState_t;
223 static findSerialPortConfigState_t findSerialPortConfigState;
225 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
227 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
229 return findNextSerialPortConfig(function);
232 const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
234 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
235 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
237 if (candidate->functionMask & function) {
238 return candidate;
241 return NULL;
244 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
246 if (!portConfig || (portConfig->functionMask & function) == 0) {
247 return PORTSHARING_UNUSED;
249 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
252 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
254 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
257 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
259 for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
260 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
262 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
263 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
264 if (!serialPortUsage) {
265 continue;
267 return serialPortUsage->serialPort;
270 return NULL;
273 #ifdef USE_TELEMETRY
274 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
275 #else
276 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
277 #endif
279 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
281 UNUSED(serialConfigToCheck);
283 * rules:
284 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
285 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
286 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
287 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
288 * (serial RX using RX line, telemetry using TX line)
289 * - No other sharing combinations are valid.
291 uint8_t mspPortCount = 0;
293 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
294 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
296 if (portConfig->functionMask & FUNCTION_MSP) {
297 mspPortCount++;
298 } else if (portConfig->identifier == SERIAL_PORT_USB_VCP) {
299 // Require MSP to be enabled for the VCP port
300 return false;
303 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
304 if (bitCount > 1) {
305 // shared
306 if (bitCount > 2) {
307 return false;
310 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
311 // MSP & telemetry
312 #ifdef USE_TELEMETRY
313 } else if (telemetryCheckRxPortShared(portConfig, rxConfig()->serialrx_provider)) {
314 // serial RX & telemetry
315 #endif
316 } else {
317 // some other combination
318 return false;
323 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
324 return false;
326 return true;
329 const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
331 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
332 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index];
333 if (candidate->identifier == identifier) {
334 return candidate;
337 return NULL;
340 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
342 const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
343 return candidate != NULL && candidate->functionMask;
346 serialPort_t *openSerialPort(
347 serialPortIdentifier_e identifier,
348 serialPortFunction_e function,
349 serialReceiveCallbackPtr rxCallback,
350 void *rxCallbackData,
351 uint32_t baudRate,
352 portMode_e mode,
353 portOptions_e options)
355 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
356 UNUSED(rxCallback);
357 UNUSED(rxCallbackData);
358 UNUSED(baudRate);
359 UNUSED(mode);
360 UNUSED(options);
361 #endif
363 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
364 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
365 // not available / already in use
366 return NULL;
369 serialPort_t *serialPort = NULL;
371 switch (identifier) {
372 #ifdef USE_VCP
373 case SERIAL_PORT_USB_VCP:
374 serialPort = usbVcpOpen();
375 break;
376 #endif
378 #if defined(USE_UART)
379 #ifdef USE_UART1
380 case SERIAL_PORT_USART1:
381 #endif
382 #ifdef USE_UART2
383 case SERIAL_PORT_USART2:
384 #endif
385 #ifdef USE_UART3
386 case SERIAL_PORT_USART3:
387 #endif
388 #ifdef USE_UART4
389 case SERIAL_PORT_UART4:
390 #endif
391 #ifdef USE_UART5
392 case SERIAL_PORT_UART5:
393 #endif
394 #ifdef USE_UART6
395 case SERIAL_PORT_USART6:
396 #endif
397 #ifdef USE_UART7
398 case SERIAL_PORT_USART7:
399 #endif
400 #ifdef USE_UART8
401 case SERIAL_PORT_USART8:
402 #endif
403 #ifdef USE_UART9
404 case SERIAL_PORT_UART9:
405 #endif
406 #ifdef USE_UART10
407 case SERIAL_PORT_USART10:
408 #endif
409 #if defined(SIMULATOR_BUILD)
410 // emulate serial ports over TCP
411 serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
412 #else
413 serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
414 #endif
415 break;
416 #endif
418 #ifdef USE_SOFTSERIAL1
419 case SERIAL_PORT_SOFTSERIAL1:
420 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
421 break;
422 #endif
423 #ifdef USE_SOFTSERIAL2
424 case SERIAL_PORT_SOFTSERIAL2:
425 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
426 break;
427 #endif
428 default:
429 break;
432 if (!serialPort) {
433 return NULL;
436 serialPort->identifier = identifier;
438 serialPortUsage->function = function;
439 serialPortUsage->serialPort = serialPort;
441 return serialPort;
444 void closeSerialPort(serialPort_t *serialPort)
446 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
447 if (!serialPortUsage) {
448 // already closed
449 return;
452 // TODO wait until data has been transmitted.
453 serialPort->rxCallback = NULL;
455 serialPortUsage->function = FUNCTION_NONE;
456 serialPortUsage->serialPort = NULL;
459 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
461 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
462 UNUSED(softserialEnabled);
463 #endif
465 serialPortCount = SERIAL_PORT_COUNT;
466 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
468 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
469 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
471 if (serialPortToDisable != SERIAL_PORT_NONE) {
472 if (serialPortUsageList[index].identifier == serialPortToDisable) {
473 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
474 serialPortCount--;
478 #if !defined(SIMULATOR_BUILD)
479 else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART8) {
480 int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
481 if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
482 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
483 serialPortCount--;
486 #endif
488 else if ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
489 #ifdef USE_SOFTSERIAL1
490 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1] ||
491 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1]))
492 #endif
493 ) || (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
494 #ifdef USE_SOFTSERIAL2
495 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2] ||
496 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2]))
497 #endif
498 )) {
499 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
500 serialPortCount--;
505 void serialRemovePort(serialPortIdentifier_e identifier)
507 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
508 if (serialPortUsageList[index].identifier == identifier) {
509 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
510 serialPortCount--;
515 uint8_t serialGetAvailablePortCount(void)
517 return serialPortCount;
520 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
522 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
523 if (serialPortUsageList[index].identifier == identifier) {
524 return true;
527 return false;
530 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
532 while (!isSerialTransmitBufferEmpty(serialPort)) {
533 delay(10);
537 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
538 // Default data consumer for serialPassThrough.
539 static void nopConsumer(uint8_t data)
541 UNUSED(data);
545 A high-level serial passthrough implementation. Used by cli to start an
546 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
547 for specialized data processing.
549 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
551 waitForSerialPortToFinishTransmitting(left);
552 waitForSerialPortToFinishTransmitting(right);
554 if (!leftC)
555 leftC = &nopConsumer;
556 if (!rightC)
557 rightC = &nopConsumer;
559 LED0_OFF;
560 LED1_OFF;
562 // Either port might be open in a mode other than MODE_RXTX. We rely on
563 // serialRxBytesWaiting() to do the right thing for a TX only port. No
564 // special handling is necessary OR performed.
565 while (1) {
566 // TODO: maintain a timestamp of last data received. Use this to
567 // implement a guard interval and check for `+++` as an escape sequence
568 // to return to CLI command mode.
569 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
570 if (serialRxBytesWaiting(left)) {
571 LED0_ON;
572 uint8_t c = serialRead(left);
573 // Make sure there is space in the tx buffer
574 while (!serialTxBytesFree(right));
575 serialWrite(right, c);
576 leftC(c);
577 LED0_OFF;
579 if (serialRxBytesWaiting(right)) {
580 LED0_ON;
581 uint8_t c = serialRead(right);
582 // Make sure there is space in the tx buffer
583 while (!serialTxBytesFree(left));
584 serialWrite(left, c);
585 rightC(c);
586 LED0_OFF;
590 #endif