Adding more servos
[inav.git] / src / main / io / serial.c
blob59b7191b6918444f502a9f0abfa3cb5d78efb856
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 #if defined(SITL_BUILD)
44 #include "drivers/serial_tcp.h"
45 #endif
47 #include "drivers/light_led.h"
49 #if defined(USE_VCP)
50 #include "drivers/serial_usb_vcp.h"
51 #endif
53 #include "io/serial.h"
55 #include "fc/cli.h"
56 #include "fc/settings.h"
58 #include "msp/msp_serial.h"
60 #ifdef USE_TELEMETRY
61 #include "telemetry/telemetry.h"
62 #endif
64 static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
66 const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
67 #ifdef USE_VCP
68 SERIAL_PORT_USB_VCP,
69 #endif
70 #ifdef USE_UART1
71 SERIAL_PORT_USART1,
72 #endif
73 #ifdef USE_UART2
74 SERIAL_PORT_USART2,
75 #endif
76 #ifdef USE_UART3
77 SERIAL_PORT_USART3,
78 #endif
79 #ifdef USE_UART4
80 SERIAL_PORT_USART4,
81 #endif
82 #ifdef USE_UART5
83 SERIAL_PORT_USART5,
84 #endif
85 #ifdef USE_UART6
86 SERIAL_PORT_USART6,
87 #endif
88 #ifdef USE_UART7
89 SERIAL_PORT_USART7,
90 #endif
91 #ifdef USE_UART8
92 SERIAL_PORT_USART8,
93 #endif
94 #ifdef USE_SOFTSERIAL1
95 SERIAL_PORT_SOFTSERIAL1,
96 #endif
97 #ifdef USE_SOFTSERIAL2
98 SERIAL_PORT_SOFTSERIAL2,
99 #endif
102 static uint8_t serialPortCount;
104 const uint32_t baudRates[] = { 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
105 460800, 921600, 1000000, 1500000, 2000000, 2470000 }; // see baudRate_e
107 #define BAUD_RATE_COUNT ARRAYLEN(baudRates)
109 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
111 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
113 memset(serialConfig, 0, sizeof(serialConfig_t));
115 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
116 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
117 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
118 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_115200;
119 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
120 serialConfig->portConfigs[i].peripheral_baudrateIndex = BAUD_115200;
123 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
125 #ifdef SERIALRX_UART
126 serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART);
127 if (serialRxUartConfig) {
128 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
130 #endif
132 #ifdef GPS_UART
133 serialPortConfig_t *gpsUartConfig = serialFindPortConfiguration(GPS_UART);
134 if (gpsUartConfig) {
135 gpsUartConfig->functionMask = FUNCTION_GPS;
137 #endif
139 #ifdef SMARTAUDIO_UART
140 serialPortConfig_t *smartAudioUartConfig = serialFindPortConfiguration(SMARTAUDIO_UART);
141 if (smartAudioUartConfig) {
142 smartAudioUartConfig->functionMask = FUNCTION_VTX_SMARTAUDIO;
144 #endif
146 #ifdef USE_VCP
147 if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
148 serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
149 if (uart1Config && uart1Config->functionMask == 0) {
150 uart1Config->functionMask = FUNCTION_MSP;
153 #endif
155 serialConfig->reboot_character = SETTING_REBOOT_CHARACTER_DEFAULT;
158 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
160 uint8_t index;
162 for (index = 0; index < BAUD_RATE_COUNT; index++) {
163 if (baudRates[index] == baudRate) {
164 return index;
167 return BAUD_AUTO;
170 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
172 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
173 if (serialPortIdentifiers[index] == identifier) {
174 return index;
177 return -1;
180 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
182 uint8_t index;
183 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
184 serialPortUsage_t *candidate = &serialPortUsageList[index];
185 if (candidate->identifier == identifier) {
186 return candidate;
189 return NULL;
192 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
193 uint8_t index;
194 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
195 serialPortUsage_t *candidate = &serialPortUsageList[index];
196 if (candidate->serialPort == serialPort) {
197 return candidate;
200 return NULL;
203 typedef struct findSerialPortConfigState_s {
204 uint8_t lastIndex;
205 } findSerialPortConfigState_t;
207 static findSerialPortConfigState_t findSerialPortConfigState;
209 serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
211 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
213 return findNextSerialPortConfig(function);
216 serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
218 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
219 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++];
221 if (candidate->functionMask & function) {
222 return candidate;
225 return NULL;
228 typedef struct findSharedSerialPortState_s {
229 uint8_t lastIndex;
230 } findSharedSerialPortState_t;
232 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
234 if (!portConfig || (portConfig->functionMask & function) == 0) {
235 return PORTSHARING_UNUSED;
237 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
240 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction)
242 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
245 static findSharedSerialPortState_t findSharedSerialPortState;
247 serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction)
249 memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));
251 return findNextSharedSerialPort(functionMask, sharedWithFunction);
254 serialPort_t *findNextSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction)
256 while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
257 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
259 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
260 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
261 if (!serialPortUsage) {
262 continue;
264 return serialPortUsage->serialPort;
267 return NULL;
270 #define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
271 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK | FUNCTION_LOG)
273 bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
275 UNUSED(serialConfigToCheck);
277 * rules:
278 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
279 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox OR debug trace.
280 * - serial RX and FrSky / LTM telemetry can be shared
281 * - No other sharing combinations are valid.
283 uint8_t mspPortCount = 0;
285 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
286 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
288 if (portConfig->functionMask & FUNCTION_MSP) {
289 mspPortCount++;
292 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
293 if (bitCount > 1) {
294 // shared
295 if (bitCount > 2) {
296 return false;
299 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
300 // MSP & telemetry
301 #ifdef USE_TELEMETRY
302 } else if (telemetryCheckRxPortShared(portConfig)) {
303 // serial RX & telemetry
304 #endif
305 } else {
306 // some other combination
307 return false;
312 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
313 return false;
315 return true;
318 serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
320 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
321 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
322 if (candidate->identifier == identifier) {
323 return candidate;
326 return NULL;
329 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
331 serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
332 return candidate != NULL && candidate->functionMask;
335 #if defined(SITL_BUILD)
336 serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options)
338 return tcpOpen(USARTx, callback, rxCallbackData, baudRate, mode, options);
340 #endif
342 serialPort_t *openSerialPort(
343 serialPortIdentifier_e identifier,
344 serialPortFunction_e function,
345 serialReceiveCallbackPtr rxCallback,
346 void *rxCallbackData,
347 uint32_t baudRate,
348 portMode_t mode,
349 portOptions_t options)
351 #if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2))
352 UNUSED(rxCallback);
353 UNUSED(rxCallbackData);
354 UNUSED(baudRate);
355 UNUSED(mode);
356 UNUSED(options);
357 #endif
359 serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
360 if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
361 // not available / already in use
362 return NULL;
365 serialPort_t *serialPort = NULL;
367 switch (identifier) {
368 #ifdef USE_VCP
369 case SERIAL_PORT_USB_VCP:
370 serialPort = usbVcpOpen();
371 break;
372 #endif
373 #ifdef USE_UART1
374 case SERIAL_PORT_USART1:
375 serialPort = uartOpen(USART1, rxCallback, rxCallbackData, baudRate, mode, options);
376 break;
377 #endif
378 #ifdef USE_UART2
379 case SERIAL_PORT_USART2:
380 serialPort = uartOpen(USART2, rxCallback, rxCallbackData, baudRate, mode, options);
381 break;
382 #endif
383 #ifdef USE_UART3
384 case SERIAL_PORT_USART3:
385 serialPort = uartOpen(USART3, rxCallback, rxCallbackData, baudRate, mode, options);
386 break;
387 #endif
388 #ifdef USE_UART4
389 case SERIAL_PORT_USART4:
390 serialPort = uartOpen(UART4, rxCallback, rxCallbackData, baudRate, mode, options);
391 break;
392 #endif
393 #ifdef USE_UART5
394 case SERIAL_PORT_USART5:
395 serialPort = uartOpen(UART5, rxCallback, rxCallbackData, baudRate, mode, options);
396 break;
397 #endif
398 #ifdef USE_UART6
399 case SERIAL_PORT_USART6:
400 serialPort = uartOpen(USART6, rxCallback, rxCallbackData, baudRate, mode, options);
401 break;
402 #endif
403 #ifdef USE_UART7
404 case SERIAL_PORT_USART7:
405 serialPort = uartOpen(UART7, rxCallback, rxCallbackData, baudRate, mode, options);
406 break;
407 #endif
408 #ifdef USE_UART8
409 case SERIAL_PORT_USART8:
410 serialPort = uartOpen(UART8, rxCallback, rxCallbackData, baudRate, mode, options);
411 break;
412 #endif
413 #ifdef USE_SOFTSERIAL1
414 case SERIAL_PORT_SOFTSERIAL1:
415 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options);
416 break;
417 #endif
418 #ifdef USE_SOFTSERIAL2
419 case SERIAL_PORT_SOFTSERIAL2:
420 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options);
421 break;
422 #endif
423 default:
424 break;
427 if (!serialPort) {
428 return NULL;
431 serialPort->identifier = identifier;
433 serialPortUsage->function = function;
434 serialPortUsage->serialPort = serialPort;
436 return serialPort;
439 void closeSerialPort(serialPort_t *serialPort)
441 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
442 if (!serialPortUsage) {
443 // already closed
444 return;
447 // TODO wait until data has been transmitted.
449 serialPort->rxCallback = NULL;
451 serialPortUsage->function = FUNCTION_NONE;
452 serialPortUsage->serialPort = NULL;
455 void serialInit(bool softserialEnabled)
457 uint8_t index;
459 serialPortCount = SERIAL_PORT_COUNT;
460 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
462 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
463 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
465 if (!softserialEnabled) {
466 if (0
467 #ifdef USE_SOFTSERIAL1
468 || serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
469 #endif
470 #ifdef USE_SOFTSERIAL2
471 || serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
472 #endif
474 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
475 serialPortCount--;
481 void serialRemovePort(serialPortIdentifier_e identifier)
483 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
484 if (serialPortUsageList[index].identifier == identifier) {
485 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
486 serialPortCount--;
491 uint8_t serialGetAvailablePortCount(void)
493 return serialPortCount;
496 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
498 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
499 if (serialPortUsageList[index].identifier == identifier) {
500 return true;
503 return false;
507 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
509 while (!isSerialTransmitBufferEmpty(serialPort)) {
510 delay(10);
514 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
515 // Default data consumer for serialPassThrough.
516 static void nopConsumer(uint8_t data)
518 UNUSED(data);
522 A high-level serial passthrough implementation. Used by cli to start an
523 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
524 for specialized data processing.
526 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
527 *leftC, serialConsumer *rightC)
529 waitForSerialPortToFinishTransmitting(left);
530 waitForSerialPortToFinishTransmitting(right);
532 if (!leftC)
533 leftC = &nopConsumer;
534 if (!rightC)
535 rightC = &nopConsumer;
537 LED0_OFF;
538 LED1_OFF;
540 // Either port might be open in a mode other than MODE_RXTX. We rely on
541 // serialRxBytesWaiting() to do the right thing for a TX only port. No
542 // special handling is necessary OR performed.
543 while (1) {
544 // TODO: maintain a timestamp of last data received. Use this to
545 // implement a guard interval and check for `+++` as an escape sequence
546 // to return to CLI command mode.
547 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
548 if (serialRxBytesWaiting(left)) {
549 LED0_ON;
550 uint8_t c = serialRead(left);
551 // Make sure there is space in the tx buffer
552 while (!serialTxBytesFree(right));
553 serialWrite(right, c);
554 leftC(c);
555 LED0_OFF;
557 if (serialRxBytesWaiting(right)) {
558 LED0_ON;
559 uint8_t c = serialRead(right);
560 // Make sure there is space in the tx buffer
561 while (!serialTxBytesFree(left));
562 serialWrite(left, c);
563 rightC(c);
564 LED0_OFF;
568 #endif