Remove magic number usage. Fix limits for FP based pid controller PID
[betaflight.git] / src / main / io / serial.c
blob4c9b5c4d757d4d01db626604adfa2f1c7988f6dc
1 /*
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/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <string.h>
23 #include "platform.h"
25 #include "build_config.h"
27 #include "drivers/system.h"
28 #include "drivers/gpio.h"
29 #include "drivers/timer.h"
30 #include "drivers/serial.h"
31 #include "drivers/serial_softserial.h"
32 #include "drivers/serial_uart.h"
33 #include "drivers/serial_usb_vcp.h"
35 #include "io/serial.h"
36 #include "serial_cli.h"
37 #include "serial_msp.h"
39 #include "config/config.h"
41 #ifdef TELEMETRY
42 #include "telemetry/telemetry.h"
43 #endif
45 void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintToUpdate);
47 void cliInit(serialConfig_t *serialConfig);
49 // this exists so the user can reference scenarios by a number in the CLI instead of an unuser-friendly bitmask.
50 const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT] = {
51 SCENARIO_UNUSED,
53 // common scenarios in order of importance
54 SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH,
55 SCENARIO_GPS_ONLY,
56 SCENARIO_SERIAL_RX_ONLY,
57 SCENARIO_TELEMETRY_ONLY,
59 // other scenarios
60 SCENARIO_MSP_CLI_GPS_PASTHROUGH,
61 SCENARIO_CLI_ONLY,
62 SCENARIO_GPS_PASSTHROUGH_ONLY,
63 SCENARIO_MSP_ONLY,
64 SCENARIO_SMARTPORT_TELEMETRY_ONLY,
66 SCENARIO_BLACKBOX_ONLY,
67 SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH
70 static serialConfig_t *serialConfig;
71 static serialPort_t *serialPorts[SERIAL_PORT_COUNT];
73 #ifdef STM32F303xC
74 static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
75 #ifdef USE_VCP
76 {SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
77 #endif
78 #ifdef USE_USART1
79 {SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
80 #endif
81 #ifdef USE_USART2
82 {SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
83 #endif
84 #ifdef USE_USART3
85 {SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
86 #endif
89 const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
90 #ifdef USE_VCP
91 {SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
92 #endif
93 #ifdef USE_USART1
94 {SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
95 #endif
96 #ifdef USE_USART2
97 {SERIAL_PORT_USART2, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
98 #endif
99 #ifdef USE_USART3
100 {SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
101 #endif
104 #else
106 #ifdef CC3D
107 static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
108 #ifdef USE_VCP
109 {SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
110 #endif
111 {SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
112 {SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
113 {SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
116 const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
117 #ifdef USE_VCP
118 {SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
119 #endif
120 {SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
121 {SERIAL_PORT_USART3, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
122 {SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
124 #else
126 static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
127 {SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
128 {SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
129 #if (SERIAL_PORT_COUNT > 2)
130 {SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
131 {SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
132 #endif
135 const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
136 {SERIAL_PORT_USART1, 9600, 250000, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
137 {SERIAL_PORT_USART2, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
138 #if (SERIAL_PORT_COUNT > 2)
139 {SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
140 {SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
141 #endif
143 #endif
144 #endif
146 const functionConstraint_t functionConstraints[] = {
147 { FUNCTION_CLI, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
148 { FUNCTION_GPS, 9600, 115200, AUTOBAUD, SPF_NONE },
149 { FUNCTION_GPS_PASSTHROUGH, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
150 { FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
151 { FUNCTION_SERIAL_RX, 9600, 250000, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
152 { FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE },
153 { FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE },
154 { FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE }
157 #define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
159 typedef struct serialPortSearchResult_s {
160 serialPortIndex_e portIndex;
161 serialPortFunction_t *portFunction;
162 const serialPortConstraint_t *portConstraint;
163 const functionConstraint_t *functionConstraint;
165 // private
166 uint8_t startSerialPortFunctionIndex; // used by findNextSerialPort
167 } serialPortSearchResult_t;
169 static const serialPortFunctionList_t serialPortFunctionList = {
170 SERIAL_PORT_COUNT,
171 serialPortFunctions
174 const serialPortFunctionList_t *getSerialPortFunctionList(void)
176 return &serialPortFunctionList;
179 uint8_t lookupScenarioIndex(serialPortFunctionScenario_e scenario) {
180 uint8_t index;
181 for (index = 0; index < SERIAL_PORT_SCENARIO_COUNT; index++) {
182 if (serialPortScenarios[index] == scenario) {
183 break;
186 return index;
189 static serialPortIndex_e lookupSerialPortIndexByIdentifier(serialPortIdentifier_e identifier)
191 serialPortIndex_e portIndex;
192 for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
193 if (serialPortConstraints[portIndex].identifier == identifier) {
194 break;
197 return portIndex;
200 #define IDENTIFIER_NOT_FOUND 0xFF
202 static uint8_t lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier_e identifier)
204 uint8_t index;
205 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
206 if (serialPortFunctions[index].identifier == identifier) {
207 return index;
210 return IDENTIFIER_NOT_FOUND;
213 static const functionConstraint_t *findFunctionConstraint(serialPortFunction_e function)
215 const functionConstraint_t *functionConstraint = NULL;
216 uint8_t functionConstraintIndex;
218 for (functionConstraintIndex = 0; functionConstraintIndex < FUNCTION_CONSTRAINT_COUNT; functionConstraintIndex++) {
219 functionConstraint = &functionConstraints[functionConstraintIndex];
220 if (functionConstraint->function == function) {
221 return functionConstraint;
224 return NULL;
227 static uint8_t countBits_uint32(uint32_t n) {
228 uint8_t c; // c accumulates the total bits set in n
229 for (c = 0; n; c++)
230 n &= n - 1; // clear the least significant bit set
231 return c;
233 static int serialPortFunctionMostSpecificFirstComparator(const void *aPtr, const void *bPtr)
235 serialPortFunction_t *a = (serialPortFunction_t *)aPtr;
236 serialPortFunction_t *b = (serialPortFunction_t *)bPtr;
238 return countBits_uint32(a->scenario) - countBits_uint32(b->scenario);
241 static void sortSerialPortFunctions(serialPortFunction_t *serialPortFunctions, uint8_t elements)
243 serialPortFunction_t swap;
245 int index1;
246 int index2;
248 // bubble-sort array (TODO - port selection can be implemented as repeated minimum search with bitmask marking used elements)
249 for (index1 = 0; index1 < (elements - 1); index1++) {
250 for (index2 = 0; index2 < elements - index1 - 1; index2++) {
251 if(serialPortFunctionMostSpecificFirstComparator(&serialPortFunctions[index2], &serialPortFunctions[index2 + 1]) > 0) {
252 swap = serialPortFunctions[index2];
253 serialPortFunctions[index2] = serialPortFunctions[index2 + 1];
254 serialPortFunctions[index2 + 1] = swap;
260 serialPortSearchResult_t *findNextSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint, serialPortSearchResult_t *resultBuffer)
262 uint8_t serialPortFunctionIndex;
263 serialPortFunction_t *serialPortFunction;
264 for (serialPortFunctionIndex = resultBuffer->startSerialPortFunctionIndex; serialPortFunctionIndex < SERIAL_PORT_COUNT; serialPortFunctionIndex++) {
265 serialPortFunction = &serialPortFunctions[serialPortFunctionIndex];
267 if (!(serialPortFunction->scenario & function)) {
268 continue;
271 uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier);
272 const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex];
274 #if defined(CC3D)
275 if (!feature(FEATURE_SOFTSERIAL) && (
276 serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1)) {
277 continue;
279 #else
280 #if defined(USE_SOFTSERIAL1) ||(defined(USE_SOFTSERIAL2))
281 if (!feature(FEATURE_SOFTSERIAL) && (
282 serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 ||
283 serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2
284 )) {
285 continue;
287 #endif
288 #if (defined(NAZE) || defined(OLIMEXINO)) && defined(SONAR)
289 if (feature(FEATURE_SONAR) && !feature(FEATURE_RX_PARALLEL_PWM) && (serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2)) {
290 continue;
292 #endif
293 #endif
295 if ((serialPortConstraint->feature & functionConstraint->requiredSerialPortFeatures) != functionConstraint->requiredSerialPortFeatures) {
296 continue;
299 if (functionConstraint->minBaudRate < serialPortConstraint->minBaudRate || functionConstraint->maxBaudRate > serialPortConstraint->maxBaudRate) {
300 continue;
303 resultBuffer->portIndex = serialPortIndex;
304 resultBuffer->portConstraint = serialPortConstraint;
305 resultBuffer->portFunction = serialPortFunction;
306 resultBuffer->functionConstraint = functionConstraint;
308 uint8_t nextStartIndex = serialPortFunctionIndex + 1;
309 resultBuffer->startSerialPortFunctionIndex = nextStartIndex;
311 return resultBuffer;
314 return NULL;
318 * since this method, and other methods that use it, use a single instance of
319 * searchPortSearchResult be sure to copy the data out of it before it gets overwritten by another caller.
320 * If this becomes a problem perhaps change the implementation to use a destination argument.
322 static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint)
324 static serialPortSearchResult_t serialPortSearchResult;
326 memset(&serialPortSearchResult, 0, sizeof(serialPortSearchResult));
328 // FIXME this only needs to be done once, after the config has been loaded.
329 sortSerialPortFunctions(serialPortFunctions, SERIAL_PORT_COUNT);
331 return findNextSerialPort(function, functionConstraint, &serialPortSearchResult);
335 static serialPortFunction_t *findSerialPortFunction(uint16_t functionMask)
337 serialPortIndex_e portIndex;
339 // find exact match first
340 for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
341 serialPortFunction_t *serialPortFunction = &serialPortFunctions[portIndex];
342 if (serialPortFunction->scenario == functionMask) {
343 return serialPortFunction;
347 // find the first port that supports the function requested
348 for (portIndex = 0; portIndex < SERIAL_PORT_COUNT; portIndex++) {
349 serialPortFunction_t *serialPortFunction = &serialPortFunctions[portIndex];
350 if (serialPortFunction->scenario & functionMask) {
351 return serialPortFunction;
355 return NULL;
359 * find a serial port that is:
360 * a) open
361 * b) matches the function mask exactly, or if an exact match is not found the first port that supports the function
363 serialPort_t *findOpenSerialPort(uint16_t functionMask)
365 serialPortFunction_t *function = findSerialPortFunction(functionMask);
366 if (!function) {
367 return NULL;
369 return function->port;
374 static serialPortFunction_t * findSerialPortFunctionByPort(serialPort_t *port)
376 serialPortFunction_t *serialPortFunction;
377 uint8_t functionIndex;
379 for (functionIndex = 0; functionIndex < SERIAL_PORT_COUNT; functionIndex++) {
380 serialPortFunction = &serialPortFunctions[functionIndex];
381 if (serialPortFunction->port == port) {
382 return serialPortFunction;
386 return NULL;
389 void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
391 serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
393 serialPortFunction->currentFunction = function;
396 void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
398 UNUSED(function);
399 serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
401 serialPortFunction->currentFunction = FUNCTION_NONE;
402 serialPortFunction->port = NULL;
405 functionConstraint_t *getConfiguredFunctionConstraint(serialPortFunction_e function)
407 static functionConstraint_t configuredFunctionConstraint;
408 const functionConstraint_t *functionConstraint;
410 functionConstraint = findFunctionConstraint(function);
411 if (!functionConstraint) {
412 return NULL;
414 memcpy(&configuredFunctionConstraint, functionConstraint, sizeof(functionConstraint_t));
416 switch(function) {
417 case FUNCTION_MSP:
418 configuredFunctionConstraint.maxBaudRate = serialConfig->msp_baudrate;
419 break;
421 case FUNCTION_CLI:
422 configuredFunctionConstraint.minBaudRate = serialConfig->cli_baudrate;
423 configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
424 break;
426 case FUNCTION_GPS_PASSTHROUGH:
427 configuredFunctionConstraint.minBaudRate = serialConfig->gps_passthrough_baudrate;
428 configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
429 break;
431 #ifdef TELEMETRY
432 case FUNCTION_TELEMETRY:
433 case FUNCTION_SMARTPORT_TELEMETRY:
434 configuredFunctionConstraint.minBaudRate = getTelemetryProviderBaudRate();
435 configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
436 break;
437 #endif
438 #ifdef SERIAL_RX
439 case FUNCTION_SERIAL_RX:
440 updateSerialRxFunctionConstraint(&configuredFunctionConstraint);
441 break;
442 #endif
443 case FUNCTION_GPS:
444 configuredFunctionConstraint.maxBaudRate = serialConfig->gps_baudrate;
445 break;
446 default:
447 break;
449 return &configuredFunctionConstraint;
452 bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
454 serialPortSearchResult_t *searchResult;
455 functionConstraint_t *functionConstraint;
457 serialConfig = serialConfigToCheck;
459 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_MSP);
460 searchResult = findSerialPort(FUNCTION_MSP, functionConstraint);
461 if (!searchResult) {
462 return false;
465 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_CLI);
466 searchResult = findSerialPort(FUNCTION_CLI, functionConstraint);
467 if (!searchResult) {
468 return false;
471 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_GPS);
472 searchResult = findSerialPort(FUNCTION_GPS, functionConstraint);
473 if (feature(FEATURE_GPS) && !searchResult) {
474 return false;
477 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_SERIAL_RX);
478 searchResult = findSerialPort(FUNCTION_SERIAL_RX, functionConstraint);
479 if (feature(FEATURE_RX_SERIAL) && !searchResult) {
480 return false;
483 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_TELEMETRY);
484 searchResult = findSerialPort(FUNCTION_TELEMETRY, functionConstraint);
485 // TODO check explicitly for SmartPort config
486 if (!searchResult) {
487 functionConstraint = getConfiguredFunctionConstraint(FUNCTION_SMARTPORT_TELEMETRY);
488 searchResult = findSerialPort(FUNCTION_SMARTPORT_TELEMETRY, functionConstraint);
490 if (feature(FEATURE_TELEMETRY) && !searchResult) {
491 return false;
494 uint8_t functionIndex;
495 uint8_t cliPortCount = 0;
496 uint8_t mspPortCount = 0;
497 for (functionIndex = 0; functionIndex < SERIAL_PORT_COUNT; functionIndex++) {
498 if (serialPortFunctions[functionIndex].scenario & FUNCTION_CLI) {
499 if (++cliPortCount > 1) {
500 return false;
503 if (serialPortFunctions[functionIndex].scenario & FUNCTION_MSP) {
504 if (++mspPortCount > MAX_MSP_PORT_COUNT) {
505 return false;
509 return true;
512 bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier)
514 serialPortSearchResult_t *searchResult;
515 const functionConstraint_t *functionConstraint;
516 serialPortFunction_e function;
518 uint8_t index;
519 for (index = 0; index < FUNCTION_CONSTRAINT_COUNT; index++) {
520 function = functionConstraints[index].function;
521 functionConstraint = findFunctionConstraint(function);
522 searchResult = findSerialPort(function, functionConstraint);
523 if (searchResult->portConstraint->identifier == portIdentifier) {
524 return true;
527 return false;
530 bool canOpenSerialPort(serialPortFunction_e function)
532 functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(function);
534 serialPortSearchResult_t *result = findSerialPort(function, functionConstraint);
535 return result != NULL;
538 bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask)
540 functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(functionToUse);
541 serialPortSearchResult_t *result = findSerialPort(functionToUse, functionConstraint);
542 if (!result) {
543 return false;
546 return result->portFunction->scenario & functionMask;
549 serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t functionMask)
551 functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(functionToUse);
552 serialPortSearchResult_t *result = findSerialPort(functionToUse, functionConstraint);
554 if (result->portFunction->scenario & functionMask) {
555 return result->portFunction->port;
557 return NULL;
560 void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
562 uint32_t portIndex = 0, serialPortIdentifier, constraintIndex;
564 for (constraintIndex = 0; constraintIndex < SERIAL_PORT_COUNT && portIndex < SERIAL_PORT_COUNT; constraintIndex++) {
565 serialPortIdentifier = serialPortConstraints[constraintIndex].identifier;
566 uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
567 if (functionIndex == IDENTIFIER_NOT_FOUND) {
568 continue;
570 serialPortFunctions[functionIndex].scenario = serialPortScenarios[serialConfig->serial_port_scenario[portIndex++]];
574 serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
576 serialPort_t *serialPort = NULL;
578 functionConstraint_t *initialFunctionConstraint = getConfiguredFunctionConstraint(function);
580 functionConstraint_t updatedFunctionConstraint;
581 memcpy(&updatedFunctionConstraint, initialFunctionConstraint, sizeof(updatedFunctionConstraint));
582 if (initialFunctionConstraint->autoBaud == NO_AUTOBAUD) {
583 updatedFunctionConstraint.minBaudRate = baudRate;
584 updatedFunctionConstraint.maxBaudRate = baudRate;
586 functionConstraint_t *functionConstraint = &updatedFunctionConstraint;
588 serialPortSearchResult_t *searchResult = findSerialPort(function, functionConstraint);
590 while(searchResult && searchResult->portFunction->port) {
591 // port is already open, find the next one
592 searchResult = findNextSerialPort(function, functionConstraint, searchResult);
595 if (!searchResult) {
596 return NULL;
599 serialPortIndex_e portIndex = searchResult->portIndex;
601 const serialPortConstraint_t *serialPortConstraint = searchResult->portConstraint;
603 serialPortIdentifier_e identifier = serialPortConstraint->identifier;
604 switch(identifier) {
605 #ifdef USE_VCP
606 case SERIAL_PORT_USB_VCP:
607 serialPort = usbVcpOpen();
608 break;
609 #endif
610 #ifdef USE_USART1
611 case SERIAL_PORT_USART1:
612 serialPort = uartOpen(USART1, callback, baudRate, mode, inversion);
613 break;
614 #endif
615 #ifdef USE_USART2
616 case SERIAL_PORT_USART2:
617 serialPort = uartOpen(USART2, callback, baudRate, mode, inversion);
618 break;
619 #endif
620 #ifdef USE_USART3
621 case SERIAL_PORT_USART3:
622 serialPort = uartOpen(USART3, callback, baudRate, mode, inversion);
623 break;
624 #endif
625 #ifdef USE_SOFTSERIAL1
626 case SERIAL_PORT_SOFTSERIAL1:
627 serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion);
628 serialSetMode(serialPort, mode);
629 break;
630 #endif
631 #ifdef USE_SOFTSERIAL2
632 case SERIAL_PORT_SOFTSERIAL2:
633 serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, inversion);
634 serialSetMode(serialPort, mode);
635 break;
636 #endif
637 default:
638 break;
641 if (!serialPort) {
642 return NULL;
645 serialPort->identifier = identifier;
647 serialPorts[portIndex] = serialPort;
649 serialPortFunction_t *serialPortFunction = searchResult->portFunction;
651 serialPortFunction->port = serialPort;
652 //serialPortFunction->identifier = identifier;
654 beginSerialPortFunction(serialPort, function);
656 return serialPort;
659 void serialInit(serialConfig_t *initialSerialConfig)
661 serialConfig = initialSerialConfig;
662 applySerialConfigToPortFunctions(serialConfig);
664 #ifdef TELEMETRY
665 if (telemetryAllowsOtherSerial(FUNCTION_MSP))
666 #endif
667 mspInit(serialConfig);
669 #ifdef TELEMETRY
670 if (telemetryAllowsOtherSerial(FUNCTION_CLI))
671 #endif
672 cliInit(serialConfig);
675 void handleSerial(void)
677 // in cli mode, all serial stuff goes to here. enter cli mode by sending #
678 if (cliMode) {
679 cliProcess();
680 return;
683 #ifdef TELEMETRY
684 if (telemetryAllowsOtherSerial(FUNCTION_MSP))
685 #endif
686 mspProcess();
689 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
691 while (!isSerialTransmitBufferEmpty(serialPort)) {
692 delay(10);
696 // evaluate all other incoming serial data
697 void evaluateOtherData(uint8_t sr)
699 if (sr == '#')
700 cliProcess();
701 else if (sr == serialConfig->reboot_character)
702 systemResetToBootloader();