[4.4.2] Remove 15 m/s limit on estimated vario (#12788)
[betaflight.git] / src / main / io / serial.c
blob8a76e063724cb874b8e4a474166d1ea34a4fa784
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 ARRAYLEN(baudRates)
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)
210 uint8_t index;
211 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
212 serialPortUsage_t *candidate = &serialPortUsageList[index];
213 if (candidate->serialPort == serialPort) {
214 return candidate;
217 return NULL;
220 typedef struct findSerialPortConfigState_s {
221 uint8_t lastIndex;
222 } findSerialPortConfigState_t;
224 static findSerialPortConfigState_t findSerialPortConfigState;
226 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
228 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
230 return findNextSerialPortConfig(function);
233 const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
235 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
236 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
238 if (candidate->functionMask & function) {
239 return candidate;
242 return NULL;
245 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
247 if (!portConfig || (portConfig->functionMask & function) == 0) {
248 return PORTSHARING_UNUSED;
250 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
253 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
255 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
258 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
260 for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
261 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
263 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
264 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
265 if (!serialPortUsage) {
266 continue;
268 return serialPortUsage->serialPort;
271 return NULL;
274 #ifdef USE_TELEMETRY
275 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP)
276 #else
277 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP)
278 #endif
280 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
282 UNUSED(serialConfigToCheck);
284 * rules:
285 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
286 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
287 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
288 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
289 * (serial RX using RX line, telemetry using TX line)
290 * - No other sharing combinations are valid.
292 uint8_t mspPortCount = 0;
294 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
295 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
297 if (portConfig->functionMask & FUNCTION_MSP) {
298 mspPortCount++;
299 } else if (portConfig->identifier == SERIAL_PORT_USB_VCP) {
300 // Require MSP to be enabled for the VCP port
301 return false;
304 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
306 #ifdef USE_VTX_MSP
307 if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
308 return false;
310 #endif
312 if (bitCount > 1) {
313 // shared
314 if (bitCount > (BITCOUNT(FUNCTION_MSP | ALL_FUNCTIONS_SHARABLE_WITH_MSP))) {
315 return false;
318 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
319 // MSP & telemetry
320 #ifdef USE_TELEMETRY
321 } else if (telemetryCheckRxPortShared(portConfig, rxConfig()->serialrx_provider)) {
322 // serial RX & telemetry
323 #endif
324 } else {
325 // some other combination
326 return false;
331 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
332 return false;
334 return true;
337 const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
339 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
340 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index];
341 if (candidate->identifier == identifier) {
342 return candidate;
345 return NULL;
348 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
350 const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
351 return candidate != NULL && candidate->functionMask;
354 serialPort_t *openSerialPort(
355 serialPortIdentifier_e identifier,
356 serialPortFunction_e function,
357 serialReceiveCallbackPtr rxCallback,
358 void *rxCallbackData,
359 uint32_t baudRate,
360 portMode_e mode,
361 portOptions_e options)
363 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
364 UNUSED(rxCallback);
365 UNUSED(rxCallbackData);
366 UNUSED(baudRate);
367 UNUSED(mode);
368 UNUSED(options);
369 #endif
371 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
372 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
373 // not available / already in use
374 return NULL;
377 serialPort_t *serialPort = NULL;
379 switch (identifier) {
380 #ifdef USE_VCP
381 case SERIAL_PORT_USB_VCP:
382 serialPort = usbVcpOpen();
383 break;
384 #endif
386 #if defined(USE_UART)
387 #ifdef USE_UART1
388 case SERIAL_PORT_USART1:
389 #endif
390 #ifdef USE_UART2
391 case SERIAL_PORT_USART2:
392 #endif
393 #ifdef USE_UART3
394 case SERIAL_PORT_USART3:
395 #endif
396 #ifdef USE_UART4
397 case SERIAL_PORT_UART4:
398 #endif
399 #ifdef USE_UART5
400 case SERIAL_PORT_UART5:
401 #endif
402 #ifdef USE_UART6
403 case SERIAL_PORT_USART6:
404 #endif
405 #ifdef USE_UART7
406 case SERIAL_PORT_USART7:
407 #endif
408 #ifdef USE_UART8
409 case SERIAL_PORT_USART8:
410 #endif
411 #ifdef USE_UART9
412 case SERIAL_PORT_UART9:
413 #endif
414 #ifdef USE_UART10
415 case SERIAL_PORT_USART10:
416 #endif
417 #ifdef USE_LPUART1
418 case SERIAL_PORT_LPUART1:
419 #endif
420 #if defined(SIMULATOR_BUILD)
421 // emulate serial ports over TCP
422 serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
423 #else
424 serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
425 #endif
426 break;
427 #endif
429 #ifdef USE_SOFTSERIAL1
430 case SERIAL_PORT_SOFTSERIAL1:
431 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
432 break;
433 #endif
434 #ifdef USE_SOFTSERIAL2
435 case SERIAL_PORT_SOFTSERIAL2:
436 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
437 break;
438 #endif
439 default:
440 break;
443 if (!serialPort) {
444 return NULL;
447 serialPort->identifier = identifier;
449 serialPortUsage->function = function;
450 serialPortUsage->serialPort = serialPort;
452 return serialPort;
455 void closeSerialPort(serialPort_t *serialPort)
457 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
458 if (!serialPortUsage) {
459 // already closed
460 return;
463 // TODO wait until data has been transmitted.
464 serialPort->rxCallback = NULL;
466 serialPortUsage->function = FUNCTION_NONE;
467 serialPortUsage->serialPort = NULL;
470 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
472 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
473 UNUSED(softserialEnabled);
474 #endif
476 serialPortCount = SERIAL_PORT_COUNT;
477 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
479 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
480 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
482 if (serialPortToDisable != SERIAL_PORT_NONE) {
483 if (serialPortUsageList[index].identifier == serialPortToDisable) {
484 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
485 serialPortCount--;
488 #if !defined(SIMULATOR_BUILD)
489 else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART10
490 #ifdef USE_LPUART1
491 || serialPortUsageList[index].identifier == SERIAL_PORT_LPUART1
492 #endif
494 int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
495 if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
496 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
497 serialPortCount--;
500 #endif
501 else if ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
502 #ifdef USE_SOFTSERIAL1
503 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1] ||
504 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1]))
505 #endif
506 ) || (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
507 #ifdef USE_SOFTSERIAL2
508 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2] ||
509 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2]))
510 #endif
511 )) {
512 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
513 serialPortCount--;
518 void serialRemovePort(serialPortIdentifier_e identifier)
520 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
521 if (serialPortUsageList[index].identifier == identifier) {
522 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
523 serialPortCount--;
528 uint8_t serialGetAvailablePortCount(void)
530 return serialPortCount;
533 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
535 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
536 if (serialPortUsageList[index].identifier == identifier) {
537 return true;
540 return false;
543 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
545 while (!isSerialTransmitBufferEmpty(serialPort)) {
546 delay(10);
550 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
551 // Default data consumer for serialPassThrough.
552 static void nopConsumer(uint8_t data)
554 UNUSED(data);
558 A high-level serial passthrough implementation. Used by cli to start an
559 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
560 for specialized data processing.
562 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
564 waitForSerialPortToFinishTransmitting(left);
565 waitForSerialPortToFinishTransmitting(right);
567 if (!leftC)
568 leftC = &nopConsumer;
569 if (!rightC)
570 rightC = &nopConsumer;
572 LED0_OFF;
573 LED1_OFF;
575 // Either port might be open in a mode other than MODE_RXTX. We rely on
576 // serialRxBytesWaiting() to do the right thing for a TX only port. No
577 // special handling is necessary OR performed.
578 while (1) {
579 // TODO: maintain a timestamp of last data received. Use this to
580 // implement a guard interval and check for `+++` as an escape sequence
581 // to return to CLI command mode.
582 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
583 if (serialRxBytesWaiting(left)) {
584 LED0_ON;
585 uint8_t c = serialRead(left);
586 // Make sure there is space in the tx buffer
587 while (!serialTxBytesFree(right));
588 serialWrite(right, c);
589 leftC(c);
590 LED0_OFF;
592 if (serialRxBytesWaiting(right)) {
593 LED0_ON;
594 uint8_t c = serialRead(right);
595 // Make sure there is space in the tx buffer
596 while (!serialTxBytesFree(left));
597 serialWrite(left, c);
598 rightC(c);
599 LED0_OFF;
603 #endif