[FLYWOOF411] add board documentation
[inav/snaewe.git] / src / main / io / serial.c
blobd8dc546c6e9c111a45f55d032c08424b4f27056c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
22 #include "platform.h"
24 #include "build/build_config.h"
27 #include "common/utils.h"
29 #include "config/parameter_group.h"
30 #include "config/parameter_group_ids.h"
32 #include "drivers/system.h"
33 #include "drivers/time.h"
34 #include "drivers/serial.h"
35 #if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
36 #include "drivers/serial_softserial.h"
37 #endif
39 #if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6)
40 #include "drivers/serial_uart.h"
41 #endif
43 #include "drivers/light_led.h"
45 #if defined(USE_VCP)
46 #include "drivers/serial_usb_vcp.h"
47 #endif
49 #include "io/serial.h"
51 #include "fc/cli.h"
53 #include "msp/msp_serial.h"
55 #ifdef USE_TELEMETRY
56 #include "telemetry/telemetry.h"
57 #endif
59 static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
61 const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
62 #ifdef USE_VCP
63 SERIAL_PORT_USB_VCP,
64 #endif
65 #ifdef USE_UART1
66 SERIAL_PORT_USART1,
67 #endif
68 #ifdef USE_UART2
69 SERIAL_PORT_USART2,
70 #endif
71 #ifdef USE_UART3
72 SERIAL_PORT_USART3,
73 #endif
74 #ifdef USE_UART4
75 SERIAL_PORT_USART4,
76 #endif
77 #ifdef USE_UART5
78 SERIAL_PORT_USART5,
79 #endif
80 #ifdef USE_UART6
81 SERIAL_PORT_USART6,
82 #endif
83 #ifdef USE_UART7
84 SERIAL_PORT_USART7,
85 #endif
86 #ifdef USE_UART8
87 SERIAL_PORT_USART8,
88 #endif
89 #ifdef USE_SOFTSERIAL1
90 SERIAL_PORT_SOFTSERIAL1,
91 #endif
92 #ifdef USE_SOFTSERIAL2
93 SERIAL_PORT_SOFTSERIAL2,
94 #endif
97 static uint8_t serialPortCount;
99 const uint32_t baudRates[] = { 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
100 460800, 921600, 1000000, 1500000, 2000000, 2470000 }; // see baudRate_e
102 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
104 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
106 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
108 memset(serialConfig, 0, sizeof(serialConfig_t));
110 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
111 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
112 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
113 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_115200;
114 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
115 serialConfig->portConfigs[i].peripheral_baudrateIndex = BAUD_115200;
118 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
120 #ifdef SERIALRX_UART
121 serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART);
122 if (serialRxUartConfig) {
123 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
125 #endif
127 #ifdef GPS_UART
128 serialPortConfig_t *gpsUartConfig = serialFindPortConfiguration(GPS_UART);
129 if (gpsUartConfig) {
130 gpsUartConfig->functionMask = FUNCTION_GPS;
132 #endif
134 #ifdef SMARTAUDIO_UART
135 serialPortConfig_t *gpsUartConfig = serialFindPortConfiguration(SMARTAUDIO_UART);
136 if (SMARTAUDIO_UART) {
137 gpsUartConfig->functionMask = FUNCTION_VTX_SMARTAUDIO;
139 #endif
141 #ifdef USE_VCP
142 if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
143 serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
144 if (uart1Config && uart1Config->functionMask == 0) {
145 uart1Config->functionMask = FUNCTION_MSP;
148 #endif
150 serialConfig->reboot_character = 'R';
153 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
155 uint8_t index;
157 for (index = 0; index < BAUD_RATE_COUNT; index++) {
158 if (baudRates[index] == baudRate) {
159 return index;
162 return BAUD_AUTO;
165 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
167 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
168 if (serialPortIdentifiers[index] == identifier) {
169 return index;
172 return -1;
175 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
177 uint8_t index;
178 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
179 serialPortUsage_t *candidate = &serialPortUsageList[index];
180 if (candidate->identifier == identifier) {
181 return candidate;
184 return NULL;
187 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
188 uint8_t index;
189 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
190 serialPortUsage_t *candidate = &serialPortUsageList[index];
191 if (candidate->serialPort == serialPort) {
192 return candidate;
195 return NULL;
198 typedef struct findSerialPortConfigState_s {
199 uint8_t lastIndex;
200 } findSerialPortConfigState_t;
202 static findSerialPortConfigState_t findSerialPortConfigState;
204 serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
206 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
208 return findNextSerialPortConfig(function);
211 serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
213 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
214 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++];
216 if (candidate->functionMask & function) {
217 return candidate;
220 return NULL;
223 typedef struct findSharedSerialPortState_s {
224 uint8_t lastIndex;
225 } findSharedSerialPortState_t;
227 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
229 if (!portConfig || (portConfig->functionMask & function) == 0) {
230 return PORTSHARING_UNUSED;
232 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
235 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction)
237 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
240 static findSharedSerialPortState_t findSharedSerialPortState;
242 serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction)
244 memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));
246 return findNextSharedSerialPort(functionMask, sharedWithFunction);
249 serialPort_t *findNextSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction)
251 while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
252 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
254 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
255 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
256 if (!serialPortUsage) {
257 continue;
259 return serialPortUsage->serialPort;
262 return NULL;
265 #define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
266 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK | FUNCTION_LOG)
268 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
270 UNUSED(serialConfigToCheck);
272 * rules:
273 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
274 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox OR debug trace.
275 * - serial RX and FrSky / LTM telemetry can be shared
276 * - No other sharing combinations are valid.
278 uint8_t mspPortCount = 0;
280 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
281 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
283 if (portConfig->functionMask & FUNCTION_MSP) {
284 mspPortCount++;
287 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
288 if (bitCount > 1) {
289 // shared
290 if (bitCount > 2) {
291 return false;
294 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
295 // MSP & telemetry
296 #ifdef USE_TELEMETRY
297 } else if (telemetryCheckRxPortShared(portConfig)) {
298 // serial RX & telemetry
299 #endif
300 } else {
301 // some other combination
302 return false;
307 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
308 return false;
310 return true;
313 serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
315 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
316 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
317 if (candidate->identifier == identifier) {
318 return candidate;
321 return NULL;
324 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
326 serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
327 return candidate != NULL && candidate->functionMask;
330 serialPort_t *openSerialPort(
331 serialPortIdentifier_e identifier,
332 serialPortFunction_e function,
333 serialReceiveCallbackPtr rxCallback,
334 void *rxCallbackData,
335 uint32_t baudRate,
336 portMode_t mode,
337 portOptions_t options)
339 #if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2))
340 UNUSED(rxCallback);
341 UNUSED(rxCallbackData);
342 UNUSED(baudRate);
343 UNUSED(mode);
344 UNUSED(options);
345 #endif
347 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
348 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
349 // not available / already in use
350 return NULL;
353 serialPort_t *serialPort = NULL;
355 switch (identifier) {
356 #ifdef USE_VCP
357 case SERIAL_PORT_USB_VCP:
358 serialPort = usbVcpOpen();
359 break;
360 #endif
361 #ifdef USE_UART1
362 case SERIAL_PORT_USART1:
363 serialPort = uartOpen(USART1, rxCallback, rxCallbackData, baudRate, mode, options);
364 break;
365 #endif
366 #ifdef USE_UART2
367 case SERIAL_PORT_USART2:
368 serialPort = uartOpen(USART2, rxCallback, rxCallbackData, baudRate, mode, options);
369 break;
370 #endif
371 #ifdef USE_UART3
372 case SERIAL_PORT_USART3:
373 serialPort = uartOpen(USART3, rxCallback, rxCallbackData, baudRate, mode, options);
374 break;
375 #endif
376 #ifdef USE_UART4
377 case SERIAL_PORT_USART4:
378 serialPort = uartOpen(UART4, rxCallback, rxCallbackData, baudRate, mode, options);
379 break;
380 #endif
381 #ifdef USE_UART5
382 case SERIAL_PORT_USART5:
383 serialPort = uartOpen(UART5, rxCallback, rxCallbackData, baudRate, mode, options);
384 break;
385 #endif
386 #ifdef USE_UART6
387 case SERIAL_PORT_USART6:
388 serialPort = uartOpen(USART6, rxCallback, rxCallbackData, baudRate, mode, options);
389 break;
390 #endif
391 #ifdef USE_UART7
392 case SERIAL_PORT_USART7:
393 serialPort = uartOpen(UART7, rxCallback, rxCallbackData, baudRate, mode, options);
394 break;
395 #endif
396 #ifdef USE_UART8
397 case SERIAL_PORT_USART8:
398 serialPort = uartOpen(UART8, rxCallback, rxCallbackData, baudRate, mode, options);
399 break;
400 #endif
401 #ifdef USE_SOFTSERIAL1
402 case SERIAL_PORT_SOFTSERIAL1:
403 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
404 break;
405 #endif
406 #ifdef USE_SOFTSERIAL2
407 case SERIAL_PORT_SOFTSERIAL2:
408 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
409 break;
410 #endif
411 default:
412 break;
415 if (!serialPort) {
416 return NULL;
419 serialPort->identifier = identifier;
421 serialPortUsage->function = function;
422 serialPortUsage->serialPort = serialPort;
424 return serialPort;
427 void closeSerialPort(serialPort_t *serialPort)
429 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
430 if (!serialPortUsage) {
431 // already closed
432 return;
435 // 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 uint8_t index;
447 serialPortCount = SERIAL_PORT_COUNT;
448 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
450 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
451 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
453 if (serialPortToDisable != SERIAL_PORT_NONE) {
454 if (serialPortUsageList[index].identifier == serialPortToDisable) {
455 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
456 serialPortCount--;
459 if (!softserialEnabled) {
460 if (0
461 #ifdef USE_SOFTSERIAL1
462 || serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
463 #endif
464 #ifdef USE_SOFTSERIAL2
465 || serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
466 #endif
468 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
469 serialPortCount--;
475 void serialRemovePort(serialPortIdentifier_e identifier)
477 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
478 if (serialPortUsageList[index].identifier == identifier) {
479 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
480 serialPortCount--;
485 uint8_t serialGetAvailablePortCount(void)
487 return serialPortCount;
490 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
492 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
493 if (serialPortUsageList[index].identifier == identifier) {
494 return true;
497 return false;
501 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
503 while (!isSerialTransmitBufferEmpty(serialPort)) {
504 delay(10);
508 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
509 // Default data consumer for serialPassThrough.
510 static void nopConsumer(uint8_t data)
512 UNUSED(data);
516 A high-level serial passthrough implementation. Used by cli to start an
517 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
518 for specialized data processing.
520 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
521 *leftC, serialConsumer *rightC)
523 waitForSerialPortToFinishTransmitting(left);
524 waitForSerialPortToFinishTransmitting(right);
526 if (!leftC)
527 leftC = &nopConsumer;
528 if (!rightC)
529 rightC = &nopConsumer;
531 LED0_OFF;
532 LED1_OFF;
534 // Either port might be open in a mode other than MODE_RXTX. We rely on
535 // serialRxBytesWaiting() to do the right thing for a TX only port. No
536 // special handling is necessary OR performed.
537 while (1) {
538 // TODO: maintain a timestamp of last data received. Use this to
539 // implement a guard interval and check for `+++` as an escape sequence
540 // to return to CLI command mode.
541 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
542 if (serialRxBytesWaiting(left)) {
543 LED0_ON;
544 uint8_t c = serialRead(left);
545 serialWrite(right, c);
546 leftC(c);
547 LED0_OFF;
549 if (serialRxBytesWaiting(right)) {
550 LED0_ON;
551 uint8_t c = serialRead(right);
552 serialWrite(left, c);
553 rightC(c);
554 LED0_OFF;
558 #endif