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"
26 #include "common/utils.h"
29 #include "pg/pg_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"
42 #include "drivers/serial_tcp.h"
45 #include "drivers/light_led.h"
48 #include "drivers/serial_usb_vcp.h"
51 #include "io/serial.h"
53 #include "interface/cli.h"
55 #include "msp/msp_serial.h"
58 #include "telemetry/telemetry.h"
63 static serialPortUsage_t serialPortUsageList
[SERIAL_PORT_COUNT
];
65 const serialPortIdentifier_e serialPortIdentifiers
[SERIAL_PORT_COUNT
] = {
93 #ifdef USE_SOFTSERIAL1
94 SERIAL_PORT_SOFTSERIAL1
,
96 #ifdef USE_SOFTSERIAL2
97 SERIAL_PORT_SOFTSERIAL2
,
101 static uint8_t serialPortCount
;
103 const uint32_t baudRates
[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
104 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
106 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
108 PG_REGISTER_WITH_RESET_FN(serialConfig_t
, serialConfig
, PG_SERIAL_CONFIG
, 0);
110 void pgResetFn_serialConfig(serialConfig_t
*serialConfig
)
112 memset(serialConfig
, 0, sizeof(serialConfig_t
));
114 for (int i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
115 serialConfig
->portConfigs
[i
].identifier
= serialPortIdentifiers
[i
];
116 serialConfig
->portConfigs
[i
].msp_baudrateIndex
= BAUD_115200
;
117 serialConfig
->portConfigs
[i
].gps_baudrateIndex
= BAUD_57600
;
118 serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
= BAUD_AUTO
;
119 serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
= BAUD_115200
;
122 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
125 serialPortConfig_t
*serialRxUartConfig
= serialFindPortConfiguration(SERIALRX_UART
);
126 if (serialRxUartConfig
) {
127 serialRxUartConfig
->functionMask
= FUNCTION_RX_SERIAL
;
131 #ifdef SBUS_TELEMETRY_UART
132 serialPortConfig_t
*serialTlemetryUartConfig
= serialFindPortConfiguration(SBUS_TELEMETRY_UART
);
133 if (serialTlemetryUartConfig
) {
134 serialTlemetryUartConfig
->functionMask
= FUNCTION_TELEMETRY_SMARTPORT
;
138 #if defined(USE_VCP) && defined(USE_MSP_UART)
139 if (serialConfig
->portConfigs
[0].identifier
== SERIAL_PORT_USB_VCP
) {
140 serialPortConfig_t
* uart1Config
= serialFindPortConfiguration(SERIAL_PORT_USART1
);
142 uart1Config
->functionMask
= FUNCTION_MSP
;
147 serialConfig
->reboot_character
= 'R';
148 serialConfig
->serial_update_rate_hz
= 100;
151 baudRate_e
lookupBaudRateIndex(uint32_t baudRate
)
155 for (index
= 0; index
< BAUD_RATE_COUNT
; index
++) {
156 if (baudRates
[index
] == baudRate
) {
163 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier
)
165 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
166 if (serialPortIdentifiers
[index
] == identifier
) {
173 serialPortUsage_t
*findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier
)
176 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
177 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
178 if (candidate
->identifier
== identifier
) {
185 serialPortUsage_t
*findSerialPortUsageByPort(serialPort_t
*serialPort
) {
187 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
188 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
189 if (candidate
->serialPort
== serialPort
) {
196 typedef struct findSerialPortConfigState_s
{
198 } findSerialPortConfigState_t
;
200 static findSerialPortConfigState_t findSerialPortConfigState
;
202 serialPortConfig_t
*findSerialPortConfig(serialPortFunction_e function
)
204 memset(&findSerialPortConfigState
, 0, sizeof(findSerialPortConfigState
));
206 return findNextSerialPortConfig(function
);
209 serialPortConfig_t
*findNextSerialPortConfig(serialPortFunction_e function
)
211 while (findSerialPortConfigState
.lastIndex
< SERIAL_PORT_COUNT
) {
212 serialPortConfig_t
*candidate
= &serialConfigMutable()->portConfigs
[findSerialPortConfigState
.lastIndex
++];
214 if (candidate
->functionMask
& function
) {
221 typedef struct findSharedSerialPortState_s
{
223 } findSharedSerialPortState_t
;
225 portSharing_e
determinePortSharing(const serialPortConfig_t
*portConfig
, serialPortFunction_e function
)
227 if (!portConfig
|| (portConfig
->functionMask
& function
) == 0) {
228 return PORTSHARING_UNUSED
;
230 return portConfig
->functionMask
== function
? PORTSHARING_NOT_SHARED
: PORTSHARING_SHARED
;
233 bool isSerialPortShared(const serialPortConfig_t
*portConfig
, uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
235 return (portConfig
) && (portConfig
->functionMask
& sharedWithFunction
) && (portConfig
->functionMask
& functionMask
);
238 static findSharedSerialPortState_t findSharedSerialPortState
;
240 serialPort_t
*findSharedSerialPort(uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
242 memset(&findSharedSerialPortState
, 0, sizeof(findSharedSerialPortState
));
244 return findNextSharedSerialPort(functionMask
, sharedWithFunction
);
247 serialPort_t
*findNextSharedSerialPort(uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
249 while (findSharedSerialPortState
.lastIndex
< SERIAL_PORT_COUNT
) {
250 const serialPortConfig_t
*candidate
= &serialConfig()->portConfigs
[findSharedSerialPortState
.lastIndex
++];
252 if (isSerialPortShared(candidate
, functionMask
, sharedWithFunction
)) {
253 const serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(candidate
->identifier
);
254 if (!serialPortUsage
) {
257 return serialPortUsage
->serialPort
;
264 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
266 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
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.
276 * (using either / or, switching based on armed / disarmed or an AUX channel if 'telemetry_switch' is true
277 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
278 * (serial RX using RX line, telemetry using TX line)
279 * - No other sharing combinations are valid.
281 uint8_t mspPortCount
= 0;
283 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
284 const serialPortConfig_t
*portConfig
= &serialConfigToCheck
->portConfigs
[index
];
286 if (portConfig
->functionMask
& FUNCTION_MSP
) {
290 uint8_t bitCount
= BITCOUNT(portConfig
->functionMask
);
297 if ((portConfig
->functionMask
& FUNCTION_MSP
) && (portConfig
->functionMask
& ALL_FUNCTIONS_SHARABLE_WITH_MSP
)) {
300 } else if (telemetryCheckRxPortShared(portConfig
)) {
301 // serial RX & telemetry
304 // some other combination
310 if (mspPortCount
== 0 || mspPortCount
> MAX_MSP_PORT_COUNT
) {
316 serialPortConfig_t
*serialFindPortConfiguration(serialPortIdentifier_e identifier
)
318 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
319 serialPortConfig_t
*candidate
= &serialConfigMutable()->portConfigs
[index
];
320 if (candidate
->identifier
== identifier
) {
327 bool doesConfigurationUsePort(serialPortIdentifier_e identifier
)
329 serialPortConfig_t
*candidate
= serialFindPortConfiguration(identifier
);
330 return candidate
!= NULL
&& candidate
->functionMask
;
333 serialPort_t
*openSerialPort(
334 serialPortIdentifier_e identifier
,
335 serialPortFunction_e function
,
336 serialReceiveCallbackPtr rxCallback
,
337 void *rxCallbackData
,
340 portOptions_e options
)
342 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
344 UNUSED(rxCallbackData
);
350 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(identifier
);
351 if (!serialPortUsage
|| serialPortUsage
->function
!= FUNCTION_NONE
) {
352 // not available / already in use
356 serialPort_t
*serialPort
= NULL
;
358 switch (identifier
) {
360 case SERIAL_PORT_USB_VCP
:
361 serialPort
= usbVcpOpen();
365 #if defined(USE_UART)
367 case SERIAL_PORT_USART1
:
370 case SERIAL_PORT_USART2
:
373 case SERIAL_PORT_USART3
:
376 case SERIAL_PORT_UART4
:
379 case SERIAL_PORT_UART5
:
382 case SERIAL_PORT_USART6
:
385 case SERIAL_PORT_USART7
:
388 case SERIAL_PORT_USART8
:
391 // SITL emulates serial ports over TCP
392 serialPort
= serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
394 serialPort
= uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
399 #ifdef USE_SOFTSERIAL1
400 case SERIAL_PORT_SOFTSERIAL1
:
401 serialPort
= openSoftSerial(SOFTSERIAL1
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
404 #ifdef USE_SOFTSERIAL2
405 case SERIAL_PORT_SOFTSERIAL2
:
406 serialPort
= openSoftSerial(SOFTSERIAL2
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
417 serialPort
->identifier
= identifier
;
419 serialPortUsage
->function
= function
;
420 serialPortUsage
->serialPort
= serialPort
;
425 void closeSerialPort(serialPort_t
*serialPort
)
427 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByPort(serialPort
);
428 if (!serialPortUsage
) {
433 // TODO wait until data has been transmitted.
434 serialPort
->rxCallback
= NULL
;
436 serialPortUsage
->function
= FUNCTION_NONE
;
437 serialPortUsage
->serialPort
= NULL
;
440 void serialInit(bool softserialEnabled
, serialPortIdentifier_e serialPortToDisable
)
442 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
443 UNUSED(softserialEnabled
);
446 serialPortCount
= SERIAL_PORT_COUNT
;
447 memset(&serialPortUsageList
, 0, sizeof(serialPortUsageList
));
449 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
450 serialPortUsageList
[index
].identifier
= serialPortIdentifiers
[index
];
452 if (serialPortToDisable
!= SERIAL_PORT_NONE
) {
453 if (serialPortUsageList
[index
].identifier
== serialPortToDisable
) {
454 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
459 if ((serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL1
460 #ifdef USE_SOFTSERIAL1
461 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
] ||
462 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
]))
464 ) || (serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL2
465 #ifdef USE_SOFTSERIAL2
466 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
] ||
467 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
]))
470 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
476 void serialRemovePort(serialPortIdentifier_e identifier
)
478 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
479 if (serialPortUsageList
[index
].identifier
== identifier
) {
480 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
486 uint8_t serialGetAvailablePortCount(void)
488 return serialPortCount
;
491 bool serialIsPortAvailable(serialPortIdentifier_e identifier
)
493 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
494 if (serialPortUsageList
[index
].identifier
== identifier
) {
501 void waitForSerialPortToFinishTransmitting(serialPort_t
*serialPort
)
503 while (!isSerialTransmitBufferEmpty(serialPort
)) {
508 #if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
509 // Default data consumer for serialPassThrough.
510 static void nopConsumer(uint8_t 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
*leftC
, serialConsumer
*rightC
)
522 waitForSerialPortToFinishTransmitting(left
);
523 waitForSerialPortToFinishTransmitting(right
);
526 leftC
= &nopConsumer
;
528 rightC
= &nopConsumer
;
533 // Either port might be open in a mode other than MODE_RXTX. We rely on
534 // serialRxBytesWaiting() to do the right thing for a TX only port. No
535 // special handling is necessary OR performed.
537 // TODO: maintain a timestamp of last data received. Use this to
538 // implement a guard interval and check for `+++` as an escape sequence
539 // to return to CLI command mode.
540 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
541 if (serialRxBytesWaiting(left
)) {
543 uint8_t c
= serialRead(left
);
544 // Make sure there is space in the tx buffer
545 while (!serialTxBytesFree(right
));
546 serialWrite(right
, c
);
550 if (serialRxBytesWaiting(right
)) {
552 uint8_t c
= serialRead(right
);
553 // Make sure there is space in the tx buffer
554 while (!serialTxBytesFree(left
));
555 serialWrite(left
, c
);