2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
27 #include "build/build_config.h"
31 #include "common/utils.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"
41 #if defined(SIMULATOR_BUILD)
42 #include "drivers/serial_tcp.h"
45 #include "drivers/light_led.h"
48 #include "drivers/serial_usb_vcp.h"
51 #include "config/config.h"
53 #include "io/serial.h"
55 #include "msp/msp_serial.h"
58 #include "pg/pg_ids.h"
61 #include "telemetry/telemetry.h"
66 static serialPortUsage_t serialPortUsageList
[SERIAL_PORT_COUNT
];
68 const serialPortIdentifier_e serialPortIdentifiers
[SERIAL_PORT_COUNT
] = {
102 #ifdef USE_SOFTSERIAL1
103 SERIAL_PORT_SOFTSERIAL1
,
105 #ifdef USE_SOFTSERIAL2
106 SERIAL_PORT_SOFTSERIAL2
,
113 static uint8_t serialPortCount
;
115 const uint32_t baudRates
[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
116 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
118 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
120 serialPortConfig_t
*serialFindPortConfigurationMutable(serialPortIdentifier_e identifier
)
122 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
123 serialPortConfig_t
*candidate
= &serialConfigMutable()->portConfigs
[index
];
124 if (candidate
->identifier
== identifier
) {
131 PG_REGISTER_WITH_RESET_FN(serialConfig_t
, serialConfig
, PG_SERIAL_CONFIG
, 1);
133 void pgResetFn_serialConfig(serialConfig_t
*serialConfig
)
135 memset(serialConfig
, 0, sizeof(serialConfig_t
));
137 for (int i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
138 serialConfig
->portConfigs
[i
].identifier
= serialPortIdentifiers
[i
];
139 serialConfig
->portConfigs
[i
].msp_baudrateIndex
= BAUD_115200
;
140 serialConfig
->portConfigs
[i
].gps_baudrateIndex
= BAUD_57600
;
141 serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
= BAUD_AUTO
;
142 serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
= BAUD_115200
;
145 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
148 serialPortConfig_t
*serialRxUartConfig
= serialFindPortConfigurationMutable(SERIALRX_UART
);
149 if (serialRxUartConfig
) {
150 serialRxUartConfig
->functionMask
= FUNCTION_RX_SERIAL
;
154 #ifdef SBUS_TELEMETRY_UART
155 serialPortConfig_t
*serialTlemetryUartConfig
= serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART
);
156 if (serialTlemetryUartConfig
) {
157 serialTlemetryUartConfig
->functionMask
= FUNCTION_TELEMETRY_SMARTPORT
;
161 #if defined(USE_VCP) && defined(USE_MSP_UART)
162 if (serialConfig
->portConfigs
[0].identifier
== SERIAL_PORT_USB_VCP
) {
163 serialPortConfig_t
* uart1Config
= serialFindPortConfigurationMutable(SERIAL_PORT_USART1
);
165 uart1Config
->functionMask
= FUNCTION_MSP
;
170 serialConfig
->reboot_character
= 'R';
171 serialConfig
->serial_update_rate_hz
= 100;
174 baudRate_e
lookupBaudRateIndex(uint32_t baudRate
)
178 for (index
= 0; index
< BAUD_RATE_COUNT
; index
++) {
179 if (baudRates
[index
] == baudRate
) {
186 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier
)
188 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
189 if (serialPortIdentifiers
[index
] == identifier
) {
196 serialPortUsage_t
*findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier
)
199 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
200 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
201 if (candidate
->identifier
== identifier
) {
208 serialPortUsage_t
*findSerialPortUsageByPort(serialPort_t
*serialPort
) {
210 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
211 serialPortUsage_t
*candidate
= &serialPortUsageList
[index
];
212 if (candidate
->serialPort
== serialPort
) {
219 typedef struct findSerialPortConfigState_s
{
221 } findSerialPortConfigState_t
;
223 static findSerialPortConfigState_t findSerialPortConfigState
;
225 const serialPortConfig_t
*findSerialPortConfig(serialPortFunction_e function
)
227 memset(&findSerialPortConfigState
, 0, sizeof(findSerialPortConfigState
));
229 return findNextSerialPortConfig(function
);
232 const serialPortConfig_t
*findNextSerialPortConfig(serialPortFunction_e function
)
234 while (findSerialPortConfigState
.lastIndex
< SERIAL_PORT_COUNT
) {
235 const serialPortConfig_t
*candidate
= &serialConfig()->portConfigs
[findSerialPortConfigState
.lastIndex
++];
237 if (candidate
->functionMask
& function
) {
244 portSharing_e
determinePortSharing(const serialPortConfig_t
*portConfig
, serialPortFunction_e function
)
246 if (!portConfig
|| (portConfig
->functionMask
& function
) == 0) {
247 return PORTSHARING_UNUSED
;
249 return portConfig
->functionMask
== function
? PORTSHARING_NOT_SHARED
: PORTSHARING_SHARED
;
252 bool isSerialPortShared(const serialPortConfig_t
*portConfig
, uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
254 return (portConfig
) && (portConfig
->functionMask
& sharedWithFunction
) && (portConfig
->functionMask
& functionMask
);
257 serialPort_t
*findSharedSerialPort(uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
259 for (unsigned i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
260 const serialPortConfig_t
*candidate
= &serialConfig()->portConfigs
[i
];
262 if (isSerialPortShared(candidate
, functionMask
, sharedWithFunction
)) {
263 const serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(candidate
->identifier
);
264 if (!serialPortUsage
) {
267 return serialPortUsage
->serialPort
;
274 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
276 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
279 bool isSerialConfigValid(const serialConfig_t
*serialConfigToCheck
)
281 UNUSED(serialConfigToCheck
);
284 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
285 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
286 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
287 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
288 * (serial RX using RX line, telemetry using TX line)
289 * - No other sharing combinations are valid.
291 uint8_t mspPortCount
= 0;
293 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
294 const serialPortConfig_t
*portConfig
= &serialConfigToCheck
->portConfigs
[index
];
296 if (portConfig
->functionMask
& FUNCTION_MSP
) {
298 } else if (portConfig
->identifier
== SERIAL_PORT_USB_VCP
) {
299 // Require MSP to be enabled for the VCP port
303 uint8_t bitCount
= BITCOUNT(portConfig
->functionMask
);
310 if ((portConfig
->functionMask
& FUNCTION_MSP
) && (portConfig
->functionMask
& ALL_FUNCTIONS_SHARABLE_WITH_MSP
)) {
313 } else if (telemetryCheckRxPortShared(portConfig
, rxConfig()->serialrx_provider
)) {
314 // serial RX & telemetry
317 // some other combination
323 if (mspPortCount
== 0 || mspPortCount
> MAX_MSP_PORT_COUNT
) {
329 const serialPortConfig_t
*serialFindPortConfiguration(serialPortIdentifier_e identifier
)
331 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
332 const serialPortConfig_t
*candidate
= &serialConfig()->portConfigs
[index
];
333 if (candidate
->identifier
== identifier
) {
340 bool doesConfigurationUsePort(serialPortIdentifier_e identifier
)
342 const serialPortConfig_t
*candidate
= serialFindPortConfiguration(identifier
);
343 return candidate
!= NULL
&& candidate
->functionMask
;
346 serialPort_t
*openSerialPort(
347 serialPortIdentifier_e identifier
,
348 serialPortFunction_e function
,
349 serialReceiveCallbackPtr rxCallback
,
350 void *rxCallbackData
,
353 portOptions_e options
)
355 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
357 UNUSED(rxCallbackData
);
363 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(identifier
);
364 if (!serialPortUsage
|| serialPortUsage
->function
!= FUNCTION_NONE
) {
365 // not available / already in use
369 serialPort_t
*serialPort
= NULL
;
371 switch (identifier
) {
373 case SERIAL_PORT_USB_VCP
:
374 serialPort
= usbVcpOpen();
378 #if defined(USE_UART)
380 case SERIAL_PORT_USART1
:
383 case SERIAL_PORT_USART2
:
386 case SERIAL_PORT_USART3
:
389 case SERIAL_PORT_UART4
:
392 case SERIAL_PORT_UART5
:
395 case SERIAL_PORT_USART6
:
398 case SERIAL_PORT_USART7
:
401 case SERIAL_PORT_USART8
:
404 case SERIAL_PORT_UART9
:
407 case SERIAL_PORT_USART10
:
410 case SERIAL_PORT_LPUART1
:
412 #if defined(SIMULATOR_BUILD)
413 // emulate serial ports over TCP
414 serialPort
= serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
416 serialPort
= uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
421 #ifdef USE_SOFTSERIAL1
422 case SERIAL_PORT_SOFTSERIAL1
:
423 serialPort
= openSoftSerial(SOFTSERIAL1
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
426 #ifdef USE_SOFTSERIAL2
427 case SERIAL_PORT_SOFTSERIAL2
:
428 serialPort
= openSoftSerial(SOFTSERIAL2
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
439 serialPort
->identifier
= identifier
;
441 serialPortUsage
->function
= function
;
442 serialPortUsage
->serialPort
= serialPort
;
447 void closeSerialPort(serialPort_t
*serialPort
)
449 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByPort(serialPort
);
450 if (!serialPortUsage
) {
455 // TODO wait until data has been transmitted.
456 serialPort
->rxCallback
= NULL
;
458 serialPortUsage
->function
= FUNCTION_NONE
;
459 serialPortUsage
->serialPort
= NULL
;
462 void serialInit(bool softserialEnabled
, serialPortIdentifier_e serialPortToDisable
)
464 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
465 UNUSED(softserialEnabled
);
468 serialPortCount
= SERIAL_PORT_COUNT
;
469 memset(&serialPortUsageList
, 0, sizeof(serialPortUsageList
));
471 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
472 serialPortUsageList
[index
].identifier
= serialPortIdentifiers
[index
];
474 if (serialPortToDisable
!= SERIAL_PORT_NONE
) {
475 if (serialPortUsageList
[index
].identifier
== serialPortToDisable
) {
476 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
480 #if !defined(SIMULATOR_BUILD)
481 else if (serialPortUsageList
[index
].identifier
<= SERIAL_PORT_USART10
483 || serialPortUsageList
[index
].identifier
== SERIAL_PORT_LPUART1
486 int resourceIndex
= SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList
[index
].identifier
);
487 if (!(serialPinConfig()->ioTagTx
[resourceIndex
] || serialPinConfig()->ioTagRx
[resourceIndex
])) {
488 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
493 else if ((serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL1
494 #ifdef USE_SOFTSERIAL1
495 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
] ||
496 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
]))
498 ) || (serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL2
499 #ifdef USE_SOFTSERIAL2
500 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
] ||
501 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
]))
504 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
510 void serialRemovePort(serialPortIdentifier_e identifier
)
512 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
513 if (serialPortUsageList
[index
].identifier
== identifier
) {
514 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
520 uint8_t serialGetAvailablePortCount(void)
522 return serialPortCount
;
525 bool serialIsPortAvailable(serialPortIdentifier_e identifier
)
527 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
528 if (serialPortUsageList
[index
].identifier
== identifier
) {
535 void waitForSerialPortToFinishTransmitting(serialPort_t
*serialPort
)
537 while (!isSerialTransmitBufferEmpty(serialPort
)) {
542 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
543 // Default data consumer for serialPassThrough.
544 static void nopConsumer(uint8_t data
)
550 A high-level serial passthrough implementation. Used by cli to start an
551 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
552 for specialized data processing.
554 void serialPassthrough(serialPort_t
*left
, serialPort_t
*right
, serialConsumer
*leftC
, serialConsumer
*rightC
)
556 waitForSerialPortToFinishTransmitting(left
);
557 waitForSerialPortToFinishTransmitting(right
);
560 leftC
= &nopConsumer
;
562 rightC
= &nopConsumer
;
567 // Either port might be open in a mode other than MODE_RXTX. We rely on
568 // serialRxBytesWaiting() to do the right thing for a TX only port. No
569 // special handling is necessary OR performed.
571 // TODO: maintain a timestamp of last data received. Use this to
572 // implement a guard interval and check for `+++` as an escape sequence
573 // to return to CLI command mode.
574 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
575 if (serialRxBytesWaiting(left
)) {
577 uint8_t c
= serialRead(left
);
578 // Make sure there is space in the tx buffer
579 while (!serialTxBytesFree(right
));
580 serialWrite(right
, c
);
584 if (serialRxBytesWaiting(right
)) {
586 uint8_t c
= serialRead(right
);
587 // Make sure there is space in the tx buffer
588 while (!serialTxBytesFree(left
));
589 serialWrite(left
, c
);