Fix unused param, add PERIPH_DRIVER flag for F4, tidied up F1 and F3 in prep.
[betaflight.git] / src / main / io / serial.c
blob866b0240e23a26638ea5d2e6573304e958ef529b
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"
26 #include "common/utils.h"
28 #include "config/parameter_group.h"
29 #include "config/parameter_group_ids.h"
31 #include "fc/config.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 #ifdef SITL
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 "io/serial.h"
53 #include "fc/cli.h"
55 #include "msp/msp_serial.h"
57 #ifdef TELEMETRY
58 #include "telemetry/telemetry.h"
59 #endif
61 static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
63 const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
64 #ifdef USE_VCP
65 SERIAL_PORT_USB_VCP,
66 #endif
67 #ifdef USE_UART1
68 SERIAL_PORT_USART1,
69 #endif
70 #ifdef USE_UART2
71 SERIAL_PORT_USART2,
72 #endif
73 #ifdef USE_UART3
74 SERIAL_PORT_USART3,
75 #endif
76 #ifdef USE_UART4
77 SERIAL_PORT_UART4,
78 #endif
79 #ifdef USE_UART5
80 SERIAL_PORT_UART5,
81 #endif
82 #ifdef USE_UART6
83 SERIAL_PORT_USART6,
84 #endif
85 #ifdef USE_UART7
86 SERIAL_PORT_USART7,
87 #endif
88 #ifdef USE_UART8
89 SERIAL_PORT_USART8,
90 #endif
91 #ifdef USE_SOFTSERIAL1
92 SERIAL_PORT_SOFTSERIAL1,
93 #endif
94 #ifdef USE_SOFTSERIAL2
95 SERIAL_PORT_SOFTSERIAL2,
96 #endif
99 static uint8_t serialPortCount;
101 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
102 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
104 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
106 PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0);
108 void pgResetFn_serialConfig(serialConfig_t *serialConfig)
110 memset(serialConfig, 0, sizeof(serialConfig_t));
112 for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
113 serialConfig->portConfigs[i].identifier = serialPortIdentifiers[i];
114 serialConfig->portConfigs[i].msp_baudrateIndex = BAUD_115200;
115 serialConfig->portConfigs[i].gps_baudrateIndex = BAUD_57600;
116 serialConfig->portConfigs[i].telemetry_baudrateIndex = BAUD_AUTO;
117 serialConfig->portConfigs[i].blackbox_baudrateIndex = BAUD_115200;
120 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
122 #if defined(USE_VCP) && defined(USE_MSP_UART)
123 if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
124 serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
125 if (uart1Config) {
126 uart1Config->functionMask = FUNCTION_MSP;
129 #endif
131 #ifdef SERIALRX_UART
132 serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART);
133 if (serialRxUartConfig) {
134 serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
136 #endif
138 #ifdef SBUS_TELEMETRY_UART
139 serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfiguration(SBUS_TELEMETRY_UART);
140 if (serialTlemetryUartConfig) {
141 serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
143 #endif
145 serialConfig->reboot_character = 'R';
146 serialConfig->serial_update_rate_hz = 100;
149 baudRate_e lookupBaudRateIndex(uint32_t baudRate)
151 uint8_t index;
153 for (index = 0; index < BAUD_RATE_COUNT; index++) {
154 if (baudRates[index] == baudRate) {
155 return index;
158 return BAUD_AUTO;
161 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
163 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
164 if (serialPortIdentifiers[index] == identifier) {
165 return index;
168 return -1;
171 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
173 uint8_t index;
174 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
175 serialPortUsage_t *candidate = &serialPortUsageList[index];
176 if (candidate->identifier == identifier) {
177 return candidate;
180 return NULL;
183 serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
184 uint8_t index;
185 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
186 serialPortUsage_t *candidate = &serialPortUsageList[index];
187 if (candidate->serialPort == serialPort) {
188 return candidate;
191 return NULL;
194 typedef struct findSerialPortConfigState_s {
195 uint8_t lastIndex;
196 } findSerialPortConfigState_t;
198 static findSerialPortConfigState_t findSerialPortConfigState;
200 serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
202 memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
204 return findNextSerialPortConfig(function);
207 serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
209 while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
210 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++];
212 if (candidate->functionMask & function) {
213 return candidate;
216 return NULL;
219 typedef struct findSharedSerialPortState_s {
220 uint8_t lastIndex;
221 } findSharedSerialPortState_t;
223 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
225 if (!portConfig || (portConfig->functionMask & function) == 0) {
226 return PORTSHARING_UNUSED;
228 return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
231 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction)
233 return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
236 static findSharedSerialPortState_t findSharedSerialPortState;
238 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
240 memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));
242 return findNextSharedSerialPort(functionMask, sharedWithFunction);
245 serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
247 while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
248 const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
250 if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
251 const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
252 if (!serialPortUsage) {
253 continue;
255 return serialPortUsage->serialPort;
258 return NULL;
261 #ifdef TELEMETRY
262 #define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT)
263 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK)
264 #else
265 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
266 #endif
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.
275 * (using either / or, switching based on armed / disarmed or an AUX channel if 'telemetry_switch' is true
276 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
277 * (serial RX using RX line, telemetry using TX line)
278 * - No other sharing combinations are valid.
280 uint8_t mspPortCount = 0;
282 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
283 const serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index];
285 if (portConfig->functionMask & FUNCTION_MSP) {
286 mspPortCount++;
289 uint8_t bitCount = BITCOUNT(portConfig->functionMask);
290 if (bitCount > 1) {
291 // shared
292 if (bitCount > 2) {
293 return false;
296 if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
297 // MSP & telemetry
298 #ifdef TELEMETRY
299 } else if (telemetryCheckRxPortShared(portConfig)) {
300 // serial RX & telemetry
301 #endif
302 } else {
303 // some other combination
304 return false;
309 if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) {
310 return false;
312 return true;
315 serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
317 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
318 serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
319 if (candidate->identifier == identifier) {
320 return candidate;
323 return NULL;
326 bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
328 serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
329 return candidate != NULL && candidate->functionMask;
332 serialPort_t *openSerialPort(
333 serialPortIdentifier_e identifier,
334 serialPortFunction_e function,
335 serialReceiveCallbackPtr rxCallback,
336 uint32_t baudRate,
337 portMode_t mode,
338 portOptions_t options)
340 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
341 UNUSED(rxCallback);
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
362 #if defined(USE_UART)
363 #ifdef USE_UART1
364 case SERIAL_PORT_USART1:
365 #endif
366 #ifdef USE_UART2
367 case SERIAL_PORT_USART2:
368 #endif
369 #ifdef USE_UART3
370 case SERIAL_PORT_USART3:
371 #endif
372 #ifdef USE_UART4
373 case SERIAL_PORT_UART4:
374 #endif
375 #ifdef USE_UART5
376 case SERIAL_PORT_UART5:
377 #endif
378 #ifdef USE_UART6
379 case SERIAL_PORT_USART6:
380 #endif
381 #ifdef USE_UART7
382 case SERIAL_PORT_USART7:
383 #endif
384 #ifdef USE_UART8
385 case SERIAL_PORT_USART8:
386 #endif
387 #ifdef SITL
388 // SITL emulates serial ports over TCP
389 serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
390 #else
391 serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
392 #endif
393 break;
394 #endif
396 #ifdef USE_SOFTSERIAL1
397 case SERIAL_PORT_SOFTSERIAL1:
398 serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, baudRate, mode, options);
399 break;
400 #endif
401 #ifdef USE_SOFTSERIAL2
402 case SERIAL_PORT_SOFTSERIAL2:
403 serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, baudRate, mode, options);
404 break;
405 #endif
406 default:
407 break;
410 if (!serialPort) {
411 return NULL;
414 serialPort->identifier = identifier;
416 serialPortUsage->function = function;
417 serialPortUsage->serialPort = serialPort;
419 return serialPort;
422 void closeSerialPort(serialPort_t *serialPort)
424 serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
425 if (!serialPortUsage) {
426 // already closed
427 return;
430 // TODO wait until data has been transmitted.
432 serialPort->rxCallback = NULL;
434 serialPortUsage->function = FUNCTION_NONE;
435 serialPortUsage->serialPort = NULL;
438 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
440 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
441 UNUSED(softserialEnabled);
442 #endif
444 serialPortCount = SERIAL_PORT_COUNT;
445 memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
447 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
448 serialPortUsageList[index].identifier = serialPortIdentifiers[index];
450 if (serialPortToDisable != SERIAL_PORT_NONE) {
451 if (serialPortUsageList[index].identifier == serialPortToDisable) {
452 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
453 serialPortCount--;
457 if ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
458 #ifdef USE_SOFTSERIAL1
459 && !(softserialEnabled && serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1])
460 #endif
461 ) || (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
462 #ifdef USE_SOFTSERIAL2
463 && !(softserialEnabled && serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2])
464 #endif
465 )) {
466 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
467 serialPortCount--;
472 void serialRemovePort(serialPortIdentifier_e identifier)
474 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
475 if (serialPortUsageList[index].identifier == identifier) {
476 serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
477 serialPortCount--;
482 uint8_t serialGetAvailablePortCount(void)
484 return serialPortCount;
487 bool serialIsPortAvailable(serialPortIdentifier_e identifier)
489 for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
490 if (serialPortUsageList[index].identifier == identifier) {
491 return true;
494 return false;
497 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
499 while (!isSerialTransmitBufferEmpty(serialPort)) {
500 delay(10);
504 void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar)
506 #ifndef USE_CLI
507 UNUSED(serialPort);
508 #else
509 if (receivedChar == '#') {
510 cliEnter(serialPort);
512 #endif
513 if (receivedChar == serialConfig()->reboot_character) {
514 systemResetToBootloader();
518 #if defined(GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
519 // Default data consumer for serialPassThrough.
520 static void nopConsumer(uint8_t data)
522 UNUSED(data);
526 A high-level serial passthrough implementation. Used by cli to start an
527 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
528 for specialized data processing.
530 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC)
532 waitForSerialPortToFinishTransmitting(left);
533 waitForSerialPortToFinishTransmitting(right);
535 if (!leftC)
536 leftC = &nopConsumer;
537 if (!rightC)
538 rightC = &nopConsumer;
540 LED0_OFF;
541 LED1_OFF;
543 // Either port might be open in a mode other than MODE_RXTX. We rely on
544 // serialRxBytesWaiting() to do the right thing for a TX only port. No
545 // special handling is necessary OR performed.
546 while (1) {
547 // TODO: maintain a timestamp of last data received. Use this to
548 // implement a guard interval and check for `+++` as an escape sequence
549 // to return to CLI command mode.
550 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
551 if (serialRxBytesWaiting(left)) {
552 LED0_ON;
553 uint8_t c = serialRead(left);
554 serialWrite(right, c);
555 leftC(c);
556 LED0_OFF;
558 if (serialRxBytesWaiting(right)) {
559 LED0_ON;
560 uint8_t c = serialRead(right);
561 serialWrite(left, c);
562 rightC(c);
563 LED0_OFF;
567 #endif