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/>.
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"
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"
43 #include "drivers/light_led.h"
46 #include "drivers/serial_usb_vcp.h"
49 #include "io/serial.h"
52 #include "fc/settings.h"
54 #include "msp/msp_serial.h"
57 #include "telemetry/telemetry.h"
60 static serialPortUsage_t serialPortUsageList
[SERIAL_PORT_COUNT
];
62 const serialPortIdentifier_e serialPortIdentifiers
[SERIAL_PORT_COUNT
] = {
90 #ifdef USE_SOFTSERIAL1
91 SERIAL_PORT_SOFTSERIAL1
,
93 #ifdef USE_SOFTSERIAL2
94 SERIAL_PORT_SOFTSERIAL2
,
98 static uint8_t serialPortCount
;
100 const uint32_t baudRates
[] = { 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
101 460800, 921600, 1000000, 1500000, 2000000, 2470000 }; // see baudRate_e
103 #define BAUD_RATE_COUNT ARRAYLEN(baudRates)
105 PG_REGISTER_WITH_RESET_FN(serialConfig_t
, serialConfig
, PG_SERIAL_CONFIG
, 1);
107 void pgResetFn_serialConfig(serialConfig_t
*serialConfig
)
109 memset(serialConfig
, 0, sizeof(serialConfig_t
));
111 for (int i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
112 serialConfig
->portConfigs
[i
].identifier
= serialPortIdentifiers
[i
];
113 serialConfig
->portConfigs
[i
].msp_baudrateIndex
= BAUD_115200
;
114 serialConfig
->portConfigs
[i
].gps_baudrateIndex
= BAUD_115200
;
115 serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
= BAUD_AUTO
;
116 serialConfig
->portConfigs
[i
].peripheral_baudrateIndex
= BAUD_115200
;
119 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
122 serialPortConfig_t
*serialRxUartConfig
= serialFindPortConfiguration(SERIALRX_UART
);
123 if (serialRxUartConfig
) {
124 serialRxUartConfig
->functionMask
= FUNCTION_RX_SERIAL
;
129 serialPortConfig_t
*gpsUartConfig
= serialFindPortConfiguration(GPS_UART
);
131 gpsUartConfig
->functionMask
= FUNCTION_GPS
;
135 #ifdef SMARTAUDIO_UART
136 serialPortConfig_t
*smartAudioUartConfig
= serialFindPortConfiguration(SMARTAUDIO_UART
);
137 if (smartAudioUartConfig
) {
138 smartAudioUartConfig
->functionMask
= FUNCTION_VTX_SMARTAUDIO
;
143 if (serialConfig
->portConfigs
[0].identifier
== SERIAL_PORT_USB_VCP
) {
144 serialPortConfig_t
* uart1Config
= serialFindPortConfiguration(SERIAL_PORT_USART1
);
145 if (uart1Config
&& uart1Config
->functionMask
== 0) {
146 uart1Config
->functionMask
= FUNCTION_MSP
;
151 serialConfig
->reboot_character
= SETTING_REBOOT_CHARACTER_DEFAULT
;
154 baudRate_e
lookupBaudRateIndex(uint32_t baudRate
)
158 for (index
= 0; index
< BAUD_RATE_COUNT
; index
++) {
159 if (baudRates
[index
] == baudRate
) {
166 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier
)
168 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
169 if (serialPortIdentifiers
[index
] == identifier
) {
176 serialPortUsage_t
*findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier
)
179 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
180 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
181 if (candidate
->identifier
== identifier
) {
188 serialPortUsage_t
*findSerialPortUsageByPort(serialPort_t
*serialPort
) {
190 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
191 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
192 if (candidate
->serialPort
== serialPort
) {
199 typedef struct findSerialPortConfigState_s
{
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
) {
224 typedef struct findSharedSerialPortState_s
{
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
, uint32_t functionMask
, serialPortFunction_e sharedWithFunction
)
238 return (portConfig
) && (portConfig
->functionMask
& sharedWithFunction
) && (portConfig
->functionMask
& functionMask
);
241 static findSharedSerialPortState_t findSharedSerialPortState
;
243 serialPort_t
*findSharedSerialPort(uint32_t functionMask
, serialPortFunction_e sharedWithFunction
)
245 memset(&findSharedSerialPortState
, 0, sizeof(findSharedSerialPortState
));
247 return findNextSharedSerialPort(functionMask
, sharedWithFunction
);
250 serialPort_t
*findNextSharedSerialPort(uint32_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
) {
260 return serialPortUsage
->serialPort
;
266 #define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
267 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK | FUNCTION_LOG)
269 bool isSerialConfigValid(const serialConfig_t
*serialConfigToCheck
)
271 UNUSED(serialConfigToCheck
);
274 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
275 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox OR debug trace.
276 * - serial RX and FrSky / LTM telemetry can be shared
277 * - No other sharing combinations are valid.
279 uint8_t mspPortCount
= 0;
281 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
282 const serialPortConfig_t
*portConfig
= &serialConfigToCheck
->portConfigs
[index
];
284 if (portConfig
->functionMask
& FUNCTION_MSP
) {
288 uint8_t bitCount
= BITCOUNT(portConfig
->functionMask
);
295 if ((portConfig
->functionMask
& FUNCTION_MSP
) && (portConfig
->functionMask
& ALL_FUNCTIONS_SHARABLE_WITH_MSP
)) {
298 } else if (telemetryCheckRxPortShared(portConfig
)) {
299 // serial RX & telemetry
302 // some other combination
308 if (mspPortCount
== 0 || mspPortCount
> MAX_MSP_PORT_COUNT
) {
314 serialPortConfig_t
*serialFindPortConfiguration(serialPortIdentifier_e identifier
)
316 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
317 serialPortConfig_t
*candidate
= &serialConfigMutable()->portConfigs
[index
];
318 if (candidate
->identifier
== identifier
) {
325 bool doesConfigurationUsePort(serialPortIdentifier_e identifier
)
327 serialPortConfig_t
*candidate
= serialFindPortConfiguration(identifier
);
328 return candidate
!= NULL
&& candidate
->functionMask
;
331 serialPort_t
*openSerialPort(
332 serialPortIdentifier_e identifier
,
333 serialPortFunction_e function
,
334 serialReceiveCallbackPtr rxCallback
,
335 void *rxCallbackData
,
338 portOptions_t options
)
340 #if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2))
342 UNUSED(rxCallbackData
);
348 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(identifier
);
349 if (!serialPortUsage
|| serialPortUsage
->function
!= FUNCTION_NONE
) {
350 // not available / already in use
354 serialPort_t
*serialPort
= NULL
;
356 switch (identifier
) {
358 case SERIAL_PORT_USB_VCP
:
359 serialPort
= usbVcpOpen();
363 case SERIAL_PORT_USART1
:
364 serialPort
= uartOpen(USART1
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
368 case SERIAL_PORT_USART2
:
369 serialPort
= uartOpen(USART2
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
373 case SERIAL_PORT_USART3
:
374 serialPort
= uartOpen(USART3
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
378 case SERIAL_PORT_USART4
:
379 serialPort
= uartOpen(UART4
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
383 case SERIAL_PORT_USART5
:
384 serialPort
= uartOpen(UART5
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
388 case SERIAL_PORT_USART6
:
389 serialPort
= uartOpen(USART6
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
393 case SERIAL_PORT_USART7
:
394 serialPort
= uartOpen(UART7
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
398 case SERIAL_PORT_USART8
:
399 serialPort
= uartOpen(UART8
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
402 #ifdef USE_SOFTSERIAL1
403 case SERIAL_PORT_SOFTSERIAL1
:
404 serialPort
= openSoftSerial(SOFTSERIAL1
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
407 #ifdef USE_SOFTSERIAL2
408 case SERIAL_PORT_SOFTSERIAL2
:
409 serialPort
= openSoftSerial(SOFTSERIAL2
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
420 serialPort
->identifier
= identifier
;
422 serialPortUsage
->function
= function
;
423 serialPortUsage
->serialPort
= serialPort
;
428 void closeSerialPort(serialPort_t
*serialPort
)
430 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByPort(serialPort
);
431 if (!serialPortUsage
) {
436 // TODO wait until data has been transmitted.
438 serialPort
->rxCallback
= NULL
;
440 serialPortUsage
->function
= FUNCTION_NONE
;
441 serialPortUsage
->serialPort
= NULL
;
444 void serialInit(bool softserialEnabled
)
448 serialPortCount
= SERIAL_PORT_COUNT
;
449 memset(&serialPortUsageList
, 0, sizeof(serialPortUsageList
));
451 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
452 serialPortUsageList
[index
].identifier
= serialPortIdentifiers
[index
];
454 if (!softserialEnabled
) {
456 #ifdef USE_SOFTSERIAL1
457 || serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL1
459 #ifdef USE_SOFTSERIAL2
460 || serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL2
463 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
470 void serialRemovePort(serialPortIdentifier_e identifier
)
472 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
473 if (serialPortUsageList
[index
].identifier
== identifier
) {
474 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
480 uint8_t serialGetAvailablePortCount(void)
482 return serialPortCount
;
485 bool serialIsPortAvailable(serialPortIdentifier_e identifier
)
487 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
488 if (serialPortUsageList
[index
].identifier
== identifier
) {
496 void waitForSerialPortToFinishTransmitting(serialPort_t
*serialPort
)
498 while (!isSerialTransmitBufferEmpty(serialPort
)) {
503 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
504 // Default data consumer for serialPassThrough.
505 static void nopConsumer(uint8_t data
)
511 A high-level serial passthrough implementation. Used by cli to start an
512 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
513 for specialized data processing.
515 void serialPassthrough(serialPort_t
*left
, serialPort_t
*right
, serialConsumer
516 *leftC
, serialConsumer
*rightC
)
518 waitForSerialPortToFinishTransmitting(left
);
519 waitForSerialPortToFinishTransmitting(right
);
522 leftC
= &nopConsumer
;
524 rightC
= &nopConsumer
;
529 // Either port might be open in a mode other than MODE_RXTX. We rely on
530 // serialRxBytesWaiting() to do the right thing for a TX only port. No
531 // special handling is necessary OR performed.
533 // TODO: maintain a timestamp of last data received. Use this to
534 // implement a guard interval and check for `+++` as an escape sequence
535 // to return to CLI command mode.
536 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
537 if (serialRxBytesWaiting(left
)) {
539 uint8_t c
= serialRead(left
);
540 // Make sure there is space in the tx buffer
541 while (!serialTxBytesFree(right
));
542 serialWrite(right
, c
);
546 if (serialRxBytesWaiting(right
)) {
548 uint8_t c
= serialRead(right
);
549 // Make sure there is space in the tx buffer
550 while (!serialTxBytesFree(left
));
551 serialWrite(left
, c
);