Added generated timer definitions for STM32F7X2 universal target.
[betaflight.git] / src / main / io / serial.c
blobc7e6b61cc3439e3895669a78430f3434c1d84555
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 "common/utils.h"
31 #include "pg/pg.h"
32 #include "pg/pg_ids.h"
34 #include "fc/config.h"
36 #include "drivers/time.h"
37 #include "drivers/system.h"
38 #include "drivers/serial.h"
39 #include "drivers/serial_uart.h"
40 #if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
41 #include "drivers/serial_softserial.h"
42 #endif
44 #ifdef SITL
45 #include "drivers/serial_tcp.h"
46 #endif
48 #include "drivers/light_led.h"
50 #if defined(USE_VCP)
51 #include "drivers/serial_usb_vcp.h"
52 #endif
54 #include "io/serial.h"
56 #include "interface/cli.h"
58 #include "msp/msp_serial.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_SOFTSERIAL1
97 SERIAL_PORT_SOFTSERIAL1,
98 #endif
99 #ifdef USE_SOFTSERIAL2
100 SERIAL_PORT_SOFTSERIAL2,
101 #endif
104 static uint8_t serialPortCount;
106 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
107 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
109 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
111 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0);
113 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
115 memset(serialConfig, 0, sizeof(serialConfig_t));
117 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
118 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
119 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
120 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_57600;
121 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
122 serialConfig->portConfigs[i].blackbox_baudrateIndex = BAUD_115200;
125 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
127 #ifdef SERIALRX_UART
128 serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART);
129 if (serialRxUartConfig) {
130 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
132 #endif
134 #ifdef SBUS_TELEMETRY_UART
135 serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfiguration(SBUS_TELEMETRY_UART);
136 if (serialTlemetryUartConfig) {
137 serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
139 #endif
141 #if defined(USE_VCP) && defined(USE_MSP_UART)
142 if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
143 serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
144 if (uart1Config) {
145 uart1Config->functionMask = FUNCTION_MSP;
148 #endif
150 serialConfig->reboot_character = 'R';
151 serialConfig->serial_update_rate_hz = 100;
154 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
156 uint8_t index;
158 for (index = 0; index < BAUD_RATE_COUNT; index++) {
159 if (baudRates[index] == baudRate) {
160 return index;
163 return BAUD_AUTO;
166 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
168 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
169 if (serialPortIdentifiers[index] == identifier) {
170 return index;
173 return -1;
176 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
178 uint8_t index;
179 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
180 serialPortUsage_t *candidate = &serialPortUsageList[index];
181 if (candidate->identifier == identifier) {
182 return candidate;
185 return NULL;
188 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
189 uint8_t index;
190 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
191 serialPortUsage_t *candidate = &serialPortUsageList[index];
192 if (candidate->serialPort == serialPort) {
193 return candidate;
196 return NULL;
199 typedef struct findSerialPortConfigState_s {
200 uint8_t lastIndex;
201 } findSerialPortConfigState_t;
203 static findSerialPortConfigState_t findSerialPortConfigState;
205 serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
207 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
209 return findNextSerialPortConfig(function);
212 serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
214 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
215 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++];
217 if (candidate->functionMask & function) {
218 return candidate;
221 return NULL;
224 typedef struct findSharedSerialPortState_s {
225 uint8_t lastIndex;
226 } findSharedSerialPortState_t;
228 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
230 if (!portConfig || (portConfig->functionMask & function) == 0) {
231 return PORTSHARING_UNUSED;
233 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
236 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
238 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
241 static findSharedSerialPortState_t findSharedSerialPortState;
243 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
245 memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));
247 return findNextSharedSerialPort(functionMask, sharedWithFunction);
250 serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
252 while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
253 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
255 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
256 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
257 if (!serialPortUsage) {
258 continue;
260 return serialPortUsage->serialPort;
263 return NULL;
266 #ifdef USE_TELEMETRY
267 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
268 #else
269 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
270 #endif
272 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
274 UNUSED(serialConfigToCheck);
276 * rules:
277 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
278 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
279 * (using either / or, switching based on armed / disarmed or an AUX channel if 'telemetry_switch' is true
280 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
281 * (serial RX using RX line, telemetry using TX line)
282 * - No other sharing combinations are valid.
284 uint8_t mspPortCount = 0;
286 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
287 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
289 if (portConfig->functionMask & FUNCTION_MSP) {
290 mspPortCount++;
293 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
294 if (bitCount > 1) {
295 // shared
296 if (bitCount > 2) {
297 return false;
300 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
301 // MSP & telemetry
302 #ifdef USE_TELEMETRY
303 } else if (telemetryCheckRxPortShared(portConfig)) {
304 // serial RX & telemetry
305 #endif
306 } else {
307 // some other combination
308 return false;
313 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
314 return false;
316 return true;
319 serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
321 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
322 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
323 if (candidate->identifier == identifier) {
324 return candidate;
327 return NULL;
330 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
332 serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
333 return candidate != NULL && candidate->functionMask;
336 serialPort_t *openSerialPort(
337 serialPortIdentifier_e identifier,
338 serialPortFunction_e function,
339 serialReceiveCallbackPtr rxCallback,
340 void *rxCallbackData,
341 uint32_t baudRate,
342 portMode_e mode,
343 portOptions_e options)
345 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
346 UNUSED(rxCallback);
347 UNUSED(rxCallbackData);
348 UNUSED(baudRate);
349 UNUSED(mode);
350 UNUSED(options);
351 #endif
353 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
354 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
355 // not available / already in use
356 return NULL;
359 serialPort_t *serialPort = NULL;
361 switch (identifier) {
362 #ifdef USE_VCP
363 case SERIAL_PORT_USB_VCP:
364 serialPort = usbVcpOpen();
365 break;
366 #endif
368 #if defined(USE_UART)
369 #ifdef USE_UART1
370 case SERIAL_PORT_USART1:
371 #endif
372 #ifdef USE_UART2
373 case SERIAL_PORT_USART2:
374 #endif
375 #ifdef USE_UART3
376 case SERIAL_PORT_USART3:
377 #endif
378 #ifdef USE_UART4
379 case SERIAL_PORT_UART4:
380 #endif
381 #ifdef USE_UART5
382 case SERIAL_PORT_UART5:
383 #endif
384 #ifdef USE_UART6
385 case SERIAL_PORT_USART6:
386 #endif
387 #ifdef USE_UART7
388 case SERIAL_PORT_USART7:
389 #endif
390 #ifdef USE_UART8
391 case SERIAL_PORT_USART8:
392 #endif
393 #ifdef SITL
394 // SITL emulates serial ports over TCP
395 serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
396 #else
397 serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
398 #endif
399 break;
400 #endif
402 #ifdef USE_SOFTSERIAL1
403 case SERIAL_PORT_SOFTSERIAL1:
404 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
405 break;
406 #endif
407 #ifdef USE_SOFTSERIAL2
408 case SERIAL_PORT_SOFTSERIAL2:
409 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
410 break;
411 #endif
412 default:
413 break;
416 if (!serialPort) {
417 return NULL;
420 serialPort->identifier = identifier;
422 serialPortUsage->function = function;
423 serialPortUsage->serialPort = serialPort;
425 return serialPort;
428 void closeSerialPort(serialPort_t *serialPort)
430 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
431 if (!serialPortUsage) {
432 // already closed
433 return;
436 // TODO wait until data has been transmitted.
437 serialPort->rxCallback = NULL;
439 serialPortUsage->function = FUNCTION_NONE;
440 serialPortUsage->serialPort = NULL;
443 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
445 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
446 UNUSED(softserialEnabled);
447 #endif
449 serialPortCount = SERIAL_PORT_COUNT;
450 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
452 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
453 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
455 if (serialPortToDisable != SERIAL_PORT_NONE) {
456 if (serialPortUsageList[index].identifier == serialPortToDisable) {
457 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
458 serialPortCount--;
462 if ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
463 #ifdef USE_SOFTSERIAL1
464 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1] ||
465 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1]))
466 #endif
467 ) || (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
468 #ifdef USE_SOFTSERIAL2
469 && !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2] ||
470 serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2]))
471 #endif
472 )) {
473 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
474 serialPortCount--;
479 void serialRemovePort(serialPortIdentifier_e identifier)
481 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
482 if (serialPortUsageList[index].identifier == identifier) {
483 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
484 serialPortCount--;
489 uint8_t serialGetAvailablePortCount(void)
491 return serialPortCount;
494 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
496 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
497 if (serialPortUsageList[index].identifier == identifier) {
498 return true;
501 return false;
504 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
506 while (!isSerialTransmitBufferEmpty(serialPort)) {
507 delay(10);
511 #if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
512 // Default data consumer for serialPassThrough.
513 static void nopConsumer(uint8_t data)
515 UNUSED(data);
519 A high-level serial passthrough implementation. Used by cli to start an
520 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
521 for specialized data processing.
523 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
525 waitForSerialPortToFinishTransmitting(left);
526 waitForSerialPortToFinishTransmitting(right);
528 if (!leftC)
529 leftC = &nopConsumer;
530 if (!rightC)
531 rightC = &nopConsumer;
533 LED0_OFF;
534 LED1_OFF;
536 // Either port might be open in a mode other than MODE_RXTX. We rely on
537 // serialRxBytesWaiting() to do the right thing for a TX only port. No
538 // special handling is necessary OR performed.
539 while (1) {
540 // TODO: maintain a timestamp of last data received. Use this to
541 // implement a guard interval and check for `+++` as an escape sequence
542 // to return to CLI command mode.
543 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
544 if (serialRxBytesWaiting(left)) {
545 LED0_ON;
546 uint8_t c = serialRead(left);
547 // Make sure there is space in the tx buffer
548 while (!serialTxBytesFree(right));
549 serialWrite(right, c);
550 leftC(c);
551 LED0_OFF;
553 if (serialRxBytesWaiting(right)) {
554 LED0_ON;
555 uint8_t c = serialRead(right);
556 // Make sure there is space in the tx buffer
557 while (!serialTxBytesFree(left));
558 serialWrite(left, c);
559 rightC(c);
560 LED0_OFF;
564 #endif