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"
29 #include "common/utils.h"
32 #include "pg/pg_ids.h"
34 #include "fc/config.h"
36 #include "drivers/time.h"
37 #include "drivers/system.h"
38 #include "drivers/serial.h"
39 #include "drivers/serial_uart.h"
40 #if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
41 #include "drivers/serial_softserial.h"
45 #include "drivers/serial_tcp.h"
48 #include "drivers/light_led.h"
51 #include "drivers/serial_usb_vcp.h"
54 #include "io/serial.h"
56 #include "interface/cli.h"
58 #include "msp/msp_serial.h"
61 #include "telemetry/telemetry.h"
66 static serialPortUsage_t serialPortUsageList
[SERIAL_PORT_COUNT
];
68 const serialPortIdentifier_e serialPortIdentifiers
[SERIAL_PORT_COUNT
] = {
96 #ifdef USE_SOFTSERIAL1
97 SERIAL_PORT_SOFTSERIAL1
,
99 #ifdef USE_SOFTSERIAL2
100 SERIAL_PORT_SOFTSERIAL2
,
104 static uint8_t serialPortCount
;
106 const uint32_t baudRates
[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
107 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
109 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
111 PG_REGISTER_WITH_RESET_FN(serialConfig_t
, serialConfig
, PG_SERIAL_CONFIG
, 0);
113 void pgResetFn_serialConfig(serialConfig_t
*serialConfig
)
115 memset(serialConfig
, 0, sizeof(serialConfig_t
));
117 for (int i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
118 serialConfig
->portConfigs
[i
].identifier
= serialPortIdentifiers
[i
];
119 serialConfig
->portConfigs
[i
].msp_baudrateIndex
= BAUD_115200
;
120 serialConfig
->portConfigs
[i
].gps_baudrateIndex
= BAUD_57600
;
121 serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
= BAUD_AUTO
;
122 serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
= BAUD_115200
;
125 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
128 serialPortConfig_t
*serialRxUartConfig
= serialFindPortConfiguration(SERIALRX_UART
);
129 if (serialRxUartConfig
) {
130 serialRxUartConfig
->functionMask
= FUNCTION_RX_SERIAL
;
134 #ifdef SBUS_TELEMETRY_UART
135 serialPortConfig_t
*serialTlemetryUartConfig
= serialFindPortConfiguration(SBUS_TELEMETRY_UART
);
136 if (serialTlemetryUartConfig
) {
137 serialTlemetryUartConfig
->functionMask
= FUNCTION_TELEMETRY_SMARTPORT
;
141 #if defined(USE_VCP) && defined(USE_MSP_UART)
142 if (serialConfig
->portConfigs
[0].identifier
== SERIAL_PORT_USB_VCP
) {
143 serialPortConfig_t
* uart1Config
= serialFindPortConfiguration(SERIAL_PORT_USART1
);
145 uart1Config
->functionMask
= FUNCTION_MSP
;
150 serialConfig
->reboot_character
= 'R';
151 serialConfig
->serial_update_rate_hz
= 100;
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
, uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
238 return (portConfig
) && (portConfig
->functionMask
& sharedWithFunction
) && (portConfig
->functionMask
& functionMask
);
241 static findSharedSerialPortState_t findSharedSerialPortState
;
243 serialPort_t
*findSharedSerialPort(uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
245 memset(&findSharedSerialPortState
, 0, sizeof(findSharedSerialPortState
));
247 return findNextSharedSerialPort(functionMask
, sharedWithFunction
);
250 serialPort_t
*findNextSharedSerialPort(uint16_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
;
267 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
269 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
272 bool isSerialConfigValid(const serialConfig_t
*serialConfigToCheck
)
274 UNUSED(serialConfigToCheck
);
277 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
278 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
279 * (using either / or, switching based on armed / disarmed or an AUX channel if 'telemetry_switch' is true
280 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
281 * (serial RX using RX line, telemetry using TX line)
282 * - No other sharing combinations are valid.
284 uint8_t mspPortCount
= 0;
286 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
287 const serialPortConfig_t
*portConfig
= &serialConfigToCheck
->portConfigs
[index
];
289 if (portConfig
->functionMask
& FUNCTION_MSP
) {
293 uint8_t bitCount
= BITCOUNT(portConfig
->functionMask
);
300 if ((portConfig
->functionMask
& FUNCTION_MSP
) && (portConfig
->functionMask
& ALL_FUNCTIONS_SHARABLE_WITH_MSP
)) {
303 } else if (telemetryCheckRxPortShared(portConfig
)) {
304 // serial RX & telemetry
307 // some other combination
313 if (mspPortCount
== 0 || mspPortCount
> MAX_MSP_PORT_COUNT
) {
319 serialPortConfig_t
*serialFindPortConfiguration(serialPortIdentifier_e identifier
)
321 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
322 serialPortConfig_t
*candidate
= &serialConfigMutable()->portConfigs
[index
];
323 if (candidate
->identifier
== identifier
) {
330 bool doesConfigurationUsePort(serialPortIdentifier_e identifier
)
332 serialPortConfig_t
*candidate
= serialFindPortConfiguration(identifier
);
333 return candidate
!= NULL
&& candidate
->functionMask
;
336 serialPort_t
*openSerialPort(
337 serialPortIdentifier_e identifier
,
338 serialPortFunction_e function
,
339 serialReceiveCallbackPtr rxCallback
,
340 void *rxCallbackData
,
343 portOptions_e options
)
345 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
347 UNUSED(rxCallbackData
);
353 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(identifier
);
354 if (!serialPortUsage
|| serialPortUsage
->function
!= FUNCTION_NONE
) {
355 // not available / already in use
359 serialPort_t
*serialPort
= NULL
;
361 switch (identifier
) {
363 case SERIAL_PORT_USB_VCP
:
364 serialPort
= usbVcpOpen();
368 #if defined(USE_UART)
370 case SERIAL_PORT_USART1
:
373 case SERIAL_PORT_USART2
:
376 case SERIAL_PORT_USART3
:
379 case SERIAL_PORT_UART4
:
382 case SERIAL_PORT_UART5
:
385 case SERIAL_PORT_USART6
:
388 case SERIAL_PORT_USART7
:
391 case SERIAL_PORT_USART8
:
394 // SITL emulates serial ports over TCP
395 serialPort
= serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
397 serialPort
= uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier
), 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.
437 serialPort
->rxCallback
= NULL
;
439 serialPortUsage
->function
= FUNCTION_NONE
;
440 serialPortUsage
->serialPort
= NULL
;
443 void serialInit(bool softserialEnabled
, serialPortIdentifier_e serialPortToDisable
)
445 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
446 UNUSED(softserialEnabled
);
449 serialPortCount
= SERIAL_PORT_COUNT
;
450 memset(&serialPortUsageList
, 0, sizeof(serialPortUsageList
));
452 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
453 serialPortUsageList
[index
].identifier
= serialPortIdentifiers
[index
];
455 if (serialPortToDisable
!= SERIAL_PORT_NONE
) {
456 if (serialPortUsageList
[index
].identifier
== serialPortToDisable
) {
457 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
462 if ((serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL1
463 #ifdef USE_SOFTSERIAL1
464 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
] ||
465 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL1
]))
467 ) || (serialPortUsageList
[index
].identifier
== SERIAL_PORT_SOFTSERIAL2
468 #ifdef USE_SOFTSERIAL2
469 && !(softserialEnabled
&& (serialPinConfig()->ioTagTx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
] ||
470 serialPinConfig()->ioTagRx
[RESOURCE_SOFT_OFFSET
+ SOFTSERIAL2
]))
473 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
479 void serialRemovePort(serialPortIdentifier_e identifier
)
481 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
482 if (serialPortUsageList
[index
].identifier
== identifier
) {
483 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
489 uint8_t serialGetAvailablePortCount(void)
491 return serialPortCount
;
494 bool serialIsPortAvailable(serialPortIdentifier_e identifier
)
496 for (uint8_t index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
497 if (serialPortUsageList
[index
].identifier
== identifier
) {
504 void waitForSerialPortToFinishTransmitting(serialPort_t
*serialPort
)
506 while (!isSerialTransmitBufferEmpty(serialPort
)) {
511 #if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
512 // Default data consumer for serialPassThrough.
513 static void nopConsumer(uint8_t data
)
519 A high-level serial passthrough implementation. Used by cli to start an
520 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
521 for specialized data processing.
523 void serialPassthrough(serialPort_t
*left
, serialPort_t
*right
, serialConsumer
*leftC
, serialConsumer
*rightC
)
525 waitForSerialPortToFinishTransmitting(left
);
526 waitForSerialPortToFinishTransmitting(right
);
529 leftC
= &nopConsumer
;
531 rightC
= &nopConsumer
;
536 // Either port might be open in a mode other than MODE_RXTX. We rely on
537 // serialRxBytesWaiting() to do the right thing for a TX only port. No
538 // special handling is necessary OR performed.
540 // TODO: maintain a timestamp of last data received. Use this to
541 // implement a guard interval and check for `+++` as an escape sequence
542 // to return to CLI command mode.
543 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
544 if (serialRxBytesWaiting(left
)) {
546 uint8_t c
= serialRead(left
);
547 // Make sure there is space in the tx buffer
548 while (!serialTxBytesFree(right
));
549 serialWrite(right
, c
);
553 if (serialRxBytesWaiting(right
)) {
555 uint8_t c
= serialRead(right
);
556 // Make sure there is space in the tx buffer
557 while (!serialTxBytesFree(left
));
558 serialWrite(left
, c
);