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/maths.h"
32 #include "common/utils.h"
34 #include "drivers/time.h"
35 #include "drivers/system.h"
36 #include "drivers/serial.h"
37 #include "drivers/serial_uart.h"
38 #if defined(USE_SOFTSERIAL)
39 #include "drivers/serial_softserial.h"
42 #if defined(SIMULATOR_BUILD)
43 #include "drivers/serial_tcp.h"
46 #include "drivers/light_led.h"
49 #include "drivers/serial_usb_vcp.h"
52 #include "config/config.h"
54 #include "io/serial.h"
56 #include "msp/msp_serial.h"
59 #include "pg/pg_ids.h"
62 #include "telemetry/telemetry.h"
67 static serialPortUsage_t serialPortUsageList
[SERIAL_PORT_COUNT
];
69 const serialPortIdentifier_e serialPortIdentifiers
[SERIAL_PORT_COUNT
] = {
103 #ifdef USE_SOFTSERIAL1
104 SERIAL_PORT_SOFTSERIAL1
,
106 #ifdef USE_SOFTSERIAL2
107 SERIAL_PORT_SOFTSERIAL2
,
114 const char* serialPortNames
[SERIAL_PORT_COUNT
] = {
148 #ifdef USE_SOFTSERIAL1
151 #ifdef USE_SOFTSERIAL2
159 const uint32_t baudRates
[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
160 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
162 static serialPortConfig_t
* findInPortConfigs_identifier(const serialPortConfig_t cfgs
[], size_t count
, serialPortIdentifier_e identifier
)
164 for (unsigned i
= 0; i
< count
; i
++) {
165 if (cfgs
[i
].identifier
== identifier
) {
166 // drop const on return - wrapper function will add it back if necessary
167 return (serialPortConfig_t
*)&cfgs
[i
];
173 serialPortConfig_t
* serialFindPortConfigurationMutable(serialPortIdentifier_e identifier
)
175 return findInPortConfigs_identifier(serialConfigMutable()->portConfigs
, ARRAYLEN(serialConfigMutable()->portConfigs
), identifier
);
178 const serialPortConfig_t
* serialFindPortConfiguration(serialPortIdentifier_e identifier
)
180 return findInPortConfigs_identifier(serialConfig()->portConfigs
, ARRAYLEN(serialConfig()->portConfigs
), identifier
);
183 PG_REGISTER_WITH_RESET_FN(serialConfig_t
, serialConfig
, PG_SERIAL_CONFIG
, 1);
185 void pgResetFn_serialConfig(serialConfig_t
*serialConfig
)
187 memset(serialConfig
, 0, sizeof(serialConfig_t
));
189 for (int i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
190 serialPortConfig_t
* pCfg
= &serialConfig
->portConfigs
[i
];
191 pCfg
->identifier
= serialPortIdentifiers
[i
];
192 pCfg
->msp_baudrateIndex
= BAUD_115200
;
193 pCfg
->gps_baudrateIndex
= BAUD_57600
;
194 pCfg
->telemetry_baudrateIndex
= BAUD_AUTO
;
195 pCfg
->blackbox_baudrateIndex
= BAUD_115200
;
198 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
201 serialPortConfig_t
*uart2Config
= serialFindPortConfigurationMutable(MSP_UART
);
203 uart2Config
->functionMask
= FUNCTION_MSP
;
207 #if defined(USE_GPS) && defined(GPS_UART)
208 serialPortConfig_t
*gpsUartConfig
= serialFindPortConfigurationMutable(GPS_UART
);
210 gpsUartConfig
->functionMask
= FUNCTION_GPS
;
215 serialPortConfig_t
*serialRxUartConfig
= serialFindPortConfigurationMutable(SERIALRX_UART
);
216 if (serialRxUartConfig
) {
217 serialRxUartConfig
->functionMask
= FUNCTION_RX_SERIAL
;
221 #ifdef SBUS_TELEMETRY_UART
222 serialPortConfig_t
*serialTelemetryUartConfig
= serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART
);
223 if (serialTelemetryUartConfig
) {
224 serialTelemetryUartConfig
->functionMask
= FUNCTION_TELEMETRY_SMARTPORT
;
228 #ifdef ESC_SENSOR_UART
229 serialPortConfig_t
*escSensorUartConfig
= serialFindPortConfigurationMutable(ESC_SENSOR_UART
);
230 if (escSensorUartConfig
) {
231 escSensorUartConfig
->functionMask
= FUNCTION_ESC_SENSOR
;
236 #ifdef VTX_SMARTAUDIO_UART
237 serialPortConfig_t
*vtxSmartAudioUartConfig
= serialFindPortConfigurationMutable(VTX_SMARTAUDIO_UART
);
238 if (vtxSmartAudioUartConfig
) {
239 vtxSmartAudioUartConfig
->functionMask
= FUNCTION_VTX_SMARTAUDIO
;
243 #ifdef VTX_TRAMP_UART
244 serialPortConfig_t
*vtxTrampUartConfig
= serialFindPortConfigurationMutable(VTX_TRAMP_UART
);
245 if (vtxTrampUartConfig
) {
246 vtxTrampUartConfig
->functionMask
= FUNCTION_VTX_TRAMP
;
251 serialPortConfig_t
*vtxMspUartConfig
= serialFindPortConfigurationMutable(VTX_MSP_UART
);
252 if (vtxMspUartConfig
) {
253 vtxMspUartConfig
->functionMask
= FUNCTION_VTX_MSP
;
258 #ifdef MSP_DISPLAYPORT_UART
259 serialPortConfig_t
*displayPortUartConfig
= serialFindPortConfigurationMutable(MSP_DISPLAYPORT_UART
);
260 if (displayPortUartConfig
) {
261 displayPortUartConfig
->functionMask
= FUNCTION_VTX_MSP
| FUNCTION_MSP
;
265 #if defined(USE_MSP_UART)
266 serialPortConfig_t
* uart1Config
= serialFindPortConfigurationMutable(USE_MSP_UART
);
268 uart1Config
->functionMask
= FUNCTION_MSP
;
272 serialConfig
->reboot_character
= 'R';
273 serialConfig
->serial_update_rate_hz
= 100;
276 baudRate_e
lookupBaudRateIndex(uint32_t baudRate
)
278 for (unsigned index
= 0; index
< ARRAYLEN(baudRates
); index
++) {
279 if (baudRates
[index
] == baudRate
) {
286 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier
)
288 for (unsigned index
= 0; index
< ARRAYLEN(serialPortIdentifiers
); index
++) {
289 if (serialPortIdentifiers
[index
] == identifier
) {
296 // find serial port by name.
297 // when cmp is NULL, case-insensitive compare is used
298 // cmp is strcmp-like function
299 serialPortIdentifier_e
findSerialPortByName(const char* portName
, int (*cmp
)(const char *portName
, const char *candidate
))
301 if (!cmp
) { // use strcasecmp by default
304 for (unsigned i
= 0; i
< ARRAYLEN(serialPortNames
); i
++) {
305 if (cmp(portName
, serialPortNames
[i
]) == 0) {
306 return serialPortIdentifiers
[i
]; // 1:1 map between names and identifiers
309 return SERIAL_PORT_NONE
;
312 const char* serialName(serialPortIdentifier_e identifier
, const char* notFound
)
314 const int idx
= findSerialPortIndexByIdentifier(identifier
);
315 return idx
>= 0 ? serialPortNames
[idx
] : notFound
;
318 serialPortUsage_t
*findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier
)
320 for (serialPortUsage_t
* usage
= serialPortUsageList
; usage
< ARRAYEND(serialPortUsageList
); usage
++) {
321 if (usage
->identifier
== identifier
) {
328 serialPortUsage_t
*findSerialPortUsageByPort(const serialPort_t
*serialPort
)
330 for (serialPortUsage_t
* usage
= serialPortUsageList
; usage
< ARRAYEND(serialPortUsageList
); usage
++) {
331 if (usage
->serialPort
== serialPort
) {
338 typedef struct findSerialPortConfigState_s
{
340 } findSerialPortConfigState_t
;
342 static findSerialPortConfigState_t findSerialPortConfigState
;
344 const serialPortConfig_t
*findSerialPortConfig(serialPortFunction_e function
)
346 memset(&findSerialPortConfigState
, 0, sizeof(findSerialPortConfigState
));
348 return findNextSerialPortConfig(function
);
351 const serialPortConfig_t
*findNextSerialPortConfig(serialPortFunction_e function
)
353 while (findSerialPortConfigState
.lastIndex
< ARRAYLEN(serialConfig()->portConfigs
)) {
354 const serialPortConfig_t
*candidate
= &serialConfig()->portConfigs
[findSerialPortConfigState
.lastIndex
++];
356 if (candidate
->functionMask
& function
) {
363 portSharing_e
determinePortSharing(const serialPortConfig_t
*portConfig
, serialPortFunction_e function
)
365 if (!portConfig
|| (portConfig
->functionMask
& function
) == 0) {
366 return PORTSHARING_UNUSED
;
368 return portConfig
->functionMask
== function
? PORTSHARING_NOT_SHARED
: PORTSHARING_SHARED
;
371 bool isSerialPortShared(const serialPortConfig_t
*portConfig
, uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
373 return (portConfig
) && (portConfig
->functionMask
& sharedWithFunction
) && (portConfig
->functionMask
& functionMask
);
376 serialPort_t
*findSharedSerialPort(uint16_t functionMask
, serialPortFunction_e sharedWithFunction
)
378 for (const serialPortConfig_t
*candidate
= serialConfig()->portConfigs
;
379 candidate
< ARRAYEND(serialConfig()->portConfigs
);
381 if (isSerialPortShared(candidate
, functionMask
, sharedWithFunction
)) {
382 const serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(candidate
->identifier
);
383 if (!serialPortUsage
) {
386 return serialPortUsage
->serialPort
;
393 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK | FUNCTION_VTX_MSP)
395 #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | FUNCTION_VTX_MSP)
398 bool isSerialConfigValid(serialConfig_t
*serialConfigToCheck
)
402 * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
403 * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
404 * (using either / or, switching based on armed / disarmed or the AUX channel configured for BOXTELEMETRY)
405 * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
406 * (serial RX using RX line, telemetry using TX line)
407 * - No other sharing combinations are valid.
409 uint8_t mspPortCount
= 0;
411 for (unsigned index
= 0; index
< ARRAYLEN(serialConfigToCheck
->portConfigs
); index
++) {
412 const serialPortConfig_t
*portConfig
= &serialConfigToCheck
->portConfigs
[index
];
414 #ifdef USE_SOFTSERIAL
415 if (serialType(portConfig
->identifier
) == SERIALTYPE_SOFTSERIAL
) {
416 // Ensure MSP or serial RX is not enabled on soft serial ports
417 serialConfigToCheck
->portConfigs
[index
].functionMask
&= ~(FUNCTION_MSP
| FUNCTION_RX_SERIAL
);
418 // Ensure that the baud rate on soft serial ports is limited to 19200
419 #ifndef USE_OVERRIDE_SOFTSERIAL_BAUDRATE
420 serialConfigToCheck
->portConfigs
[index
].gps_baudrateIndex
= constrain(portConfig
->gps_baudrateIndex
, BAUD_AUTO
, BAUD_19200
);
421 serialConfigToCheck
->portConfigs
[index
].blackbox_baudrateIndex
= constrain(portConfig
->blackbox_baudrateIndex
, BAUD_AUTO
, BAUD_19200
);
422 serialConfigToCheck
->portConfigs
[index
].telemetry_baudrateIndex
= constrain(portConfig
->telemetry_baudrateIndex
, BAUD_AUTO
, BAUD_19200
);
425 #endif // USE_SOFTSERIAL
427 if (portConfig
->functionMask
& FUNCTION_MSP
) {
430 if (portConfig
->identifier
== SERIAL_PORT_USB_VCP
431 && (portConfig
->functionMask
& FUNCTION_MSP
) == 0) {
432 // Require MSP to be enabled for the VCP port
436 uint8_t bitCount
= popcount32(portConfig
->functionMask
);
439 if ((portConfig
->functionMask
& FUNCTION_VTX_MSP
) && bitCount
== 1) { // VTX MSP has to be shared with RX or MSP serial
446 if (bitCount
> (BITCOUNT(FUNCTION_MSP
| ALL_FUNCTIONS_SHARABLE_WITH_MSP
))) {
450 if ((portConfig
->functionMask
& FUNCTION_MSP
) && (portConfig
->functionMask
& ALL_FUNCTIONS_SHARABLE_WITH_MSP
)) {
453 } else if (telemetryCheckRxPortShared(portConfig
, rxConfig()->serialrx_provider
)) {
454 // serial RX & telemetry
457 // some other combination
463 if (mspPortCount
== 0 || mspPortCount
> MAX_MSP_PORT_COUNT
) {
469 bool doesConfigurationUsePort(serialPortIdentifier_e identifier
)
471 const serialPortConfig_t
*candidate
= serialFindPortConfiguration(identifier
);
472 return candidate
!= NULL
&& candidate
->functionMask
;
475 serialPort_t
*openSerialPort(
476 serialPortIdentifier_e identifier
,
477 serialPortFunction_e function
,
478 serialReceiveCallbackPtr rxCallback
,
479 void *rxCallbackData
,
482 portOptions_e options
)
484 #if !(defined(USE_UART) || defined(USE_SOFTSERIAL) || defined(USE_LPUART))
486 UNUSED(rxCallbackData
);
492 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByIdentifier(identifier
);
493 if (!serialPortUsage
|| serialPortUsage
->function
!= FUNCTION_NONE
) {
494 // not available / already in use
498 serialPort_t
*serialPort
= NULL
;
500 switch (serialType(identifier
)) {
502 case SERIALTYPE_USB_VCP
:
503 serialPort
= usbVcpOpen();
506 #if defined(USE_UART)
507 case SERIALTYPE_UART
:
508 case SERIALTYPE_LPUART
:
509 #if defined(SIMULATOR_BUILD)
510 // emulate serial ports over TCP
511 serialPort
= serTcpOpen(identifier
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
513 serialPort
= uartOpen(identifier
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
517 #ifdef USE_SOFTSERIAL
518 case SERIALTYPE_SOFTSERIAL
:
519 # if !defined(USE_OVERRIDE_SOFTSERIAL_BAUDRATE)
520 if (baudRate
> 19200) {
521 // Don't continue if baud rate requested is higher then the limit set on soft serial ports
524 # endif // !USE_OVERRIDE_SOFTSERIAL_BAUDRATE
525 serialPort
= softSerialOpen(identifier
, rxCallback
, rxCallbackData
, baudRate
, mode
, options
);
527 #endif // USE_SOFTSERIAL
536 serialPort
->identifier
= identifier
; // Some versions of *Open() set this member sooner
538 serialPortUsage
->function
= function
;
539 serialPortUsage
->serialPort
= serialPort
;
544 void closeSerialPort(serialPort_t
*serialPort
)
549 serialPortUsage_t
*serialPortUsage
= findSerialPortUsageByPort(serialPort
);
550 if (!serialPortUsage
) {
555 // TODO wait until data has been transmitted.
556 serialPort
->rxCallback
= NULL
;
558 serialPortUsage
->function
= FUNCTION_NONE
;
559 serialPortUsage
->serialPort
= NULL
;
562 void serialInit(bool softserialEnabled
, serialPortIdentifier_e serialPortToDisable
)
564 #if !defined(USE_SOFTSERIAL)
565 UNUSED(softserialEnabled
);
568 memset(&serialPortUsageList
, 0, sizeof(serialPortUsageList
));
570 for (int index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
571 serialPortUsageList
[index
].identifier
= serialPortIdentifiers
[index
];
573 if (serialPortToDisable
!= SERIAL_PORT_NONE
574 && serialPortUsageList
[index
].identifier
== serialPortToDisable
) {
575 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
576 continue; // this index is deleted
579 #if !defined(SIMULATOR_BUILD) // no serialPinConfig on SITL
580 const int resourceIndex
= serialResourceIndex(serialPortUsageList
[index
].identifier
);
581 if (resourceIndex
>= 0 // resource exists
582 && !(serialPinConfig()->ioTagTx
[resourceIndex
] || serialPinConfig()->ioTagRx
[resourceIndex
])) {
583 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
588 if (serialType(serialPortUsageList
[index
].identifier
) == SERIALTYPE_SOFTSERIAL
) {
590 #ifdef USE_SOFTSERIAL
591 && !softserialEnabled
594 serialPortUsageList
[index
].identifier
= SERIAL_PORT_NONE
;
601 void serialRemovePort(serialPortIdentifier_e identifier
)
603 serialPortUsage_t
* usage
;
604 while ((usage
= findSerialPortUsageByIdentifier(identifier
)) != NULL
) {
605 usage
->identifier
= SERIAL_PORT_NONE
;
609 bool serialIsPortAvailable(serialPortIdentifier_e identifier
)
611 return findSerialPortUsageByIdentifier(identifier
) != NULL
;
614 void waitForSerialPortToFinishTransmitting(serialPort_t
*serialPort
)
616 while (!isSerialTransmitBufferEmpty(serialPort
)) {
621 #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
622 // Default data consumer for serialPassThrough.
623 static void nopConsumer(uint8_t data
)
629 A high-level serial passthrough implementation. Used by cli to start an
630 arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
631 for specialized data processing.
633 void serialPassthrough(serialPort_t
*left
, serialPort_t
*right
, serialConsumer
*leftC
, serialConsumer
*rightC
)
635 waitForSerialPortToFinishTransmitting(left
);
636 waitForSerialPortToFinishTransmitting(right
);
639 leftC
= &nopConsumer
;
641 rightC
= &nopConsumer
;
646 // Either port might be open in a mode other than MODE_RXTX. We rely on
647 // serialRxBytesWaiting() to do the right thing for a TX only port. No
648 // special handling is necessary OR performed.
650 // TODO: maintain a timestamp of last data received. Use this to
651 // implement a guard interval and check for `+++` as an escape sequence
652 // to return to CLI command mode.
653 // https://en.wikipedia.org/wiki/Escape_sequence#Modem_control
654 if (serialRxBytesWaiting(left
)) {
656 uint8_t c
= serialRead(left
);
657 // Make sure there is space in the tx buffer
658 while (!serialTxBytesFree(right
));
659 serialWrite(right
, c
);
663 if (serialRxBytesWaiting(right
)) {
665 uint8_t c
= serialRead(right
);
666 // Make sure there is space in the tx buffer
667 while (!serialTxBytesFree(left
));
668 serialWrite(left
, c
);