Avoid resetting page cycle index when re-enabling page cycling so that
[betaflight.git] / src / main / io / serial.h
blobdb685a3271bf55c9a5fa52e6ff12ec3bda2c865b
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 #pragma once
20 typedef enum {
21 FUNCTION_NONE = 0,
22 FUNCTION_MSP = (1 << 0),
23 FUNCTION_CLI = (1 << 1),
24 FUNCTION_TELEMETRY = (1 << 2),
25 FUNCTION_SMARTPORT_TELEMETRY = (1 << 3),
26 FUNCTION_SERIAL_RX = (1 << 4),
27 FUNCTION_GPS = (1 << 5),
28 FUNCTION_GPS_PASSTHROUGH = (1 << 6),
29 FUNCTION_BLACKBOX = (1 << 7)
30 } serialPortFunction_e;
32 typedef enum {
33 NO_AUTOBAUD = 0,
34 AUTOBAUD
35 } autoBaud_e;
37 typedef struct functionConstraint_s {
38 serialPortFunction_e function;
39 uint32_t minBaudRate;
40 uint32_t maxBaudRate;
41 autoBaud_e autoBaud;
42 uint8_t requiredSerialPortFeatures;
43 } functionConstraint_t;
45 typedef enum {
46 SCENARIO_UNUSED = FUNCTION_NONE,
48 SCENARIO_CLI_ONLY = FUNCTION_CLI,
49 SCENARIO_GPS_ONLY = FUNCTION_GPS,
50 SCENARIO_GPS_PASSTHROUGH_ONLY = FUNCTION_GPS_PASSTHROUGH,
51 SCENARIO_MSP_ONLY = FUNCTION_MSP,
52 SCENARIO_MSP_CLI_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_GPS_PASSTHROUGH,
53 SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH,
54 SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX,
55 SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY,
56 SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY,
57 SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX,
58 SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH
59 } serialPortFunctionScenario_e;
61 #define SERIAL_PORT_SCENARIO_COUNT 12
62 #define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
63 extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
65 typedef enum {
66 SERIAL_PORT_1 = 0,
67 SERIAL_PORT_2,
68 #if (SERIAL_PORT_COUNT > 2)
69 SERIAL_PORT_3,
70 #if (SERIAL_PORT_COUNT > 3)
71 SERIAL_PORT_4,
72 #if (SERIAL_PORT_COUNT > 4)
73 SERIAL_PORT_5
74 #endif
75 #endif
76 #endif
77 } serialPortIndex_e;
79 // serial port identifiers are now fixed, these values are used by MSP commands.
80 typedef enum {
81 SERIAL_PORT_USART1 = 0,
82 SERIAL_PORT_USART2,
83 SERIAL_PORT_USART3,
84 SERIAL_PORT_USART4,
85 SERIAL_PORT_USB_VCP = 20,
86 SERIAL_PORT_SOFTSERIAL1 = 30,
87 SERIAL_PORT_SOFTSERIAL2,
88 SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
89 } serialPortIdentifier_e;
92 // bitmask
93 typedef enum {
94 SPF_NONE = 0,
95 SPF_SUPPORTS_CALLBACK = (1 << 0),
96 SPF_SUPPORTS_SBUS_MODE = (1 << 1),
97 SPF_SUPPORTS_BIDIR_MODE = (1 << 2),
98 SPF_IS_SOFTWARE_INVERTABLE = (1 << 3)
99 } serialPortFeature_t;
101 typedef struct serialPortConstraint_s {
102 const serialPortIdentifier_e identifier;
103 uint32_t minBaudRate;
104 uint32_t maxBaudRate;
105 serialPortFeature_t feature;
106 } serialPortConstraint_t;
107 extern const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT];
109 typedef struct serialPortFunction_s {
110 serialPortIdentifier_e identifier;
111 serialPort_t *port; // a NULL values indicates the port has not been opened yet.
112 serialPortFunctionScenario_e scenario;
113 serialPortFunction_e currentFunction;
114 } serialPortFunction_t;
116 typedef struct serialPortFunctionList_s {
117 uint8_t serialPortCount;
118 serialPortFunction_t *functions;
119 } serialPortFunctionList_t;
121 typedef struct serialConfig_s {
122 uint8_t serial_port_scenario[SERIAL_PORT_COUNT];
123 uint32_t msp_baudrate;
124 uint32_t cli_baudrate;
125 uint32_t gps_baudrate;
126 uint32_t gps_passthrough_baudrate;
128 uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
129 } serialConfig_t;
131 uint8_t lookupScenarioIndex(serialPortFunctionScenario_e scenario);
133 serialPort_t *findOpenSerialPort(uint16_t functionMask);
134 serialPort_t *openSerialPort(serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion);
136 bool canOpenSerialPort(serialPortFunction_e function);
137 void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
138 void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function);
140 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
142 void applySerialConfigToPortFunctions(serialConfig_t *serialConfig);
143 bool isSerialConfigValid(serialConfig_t *serialConfig);
144 bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
145 bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask);
146 serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t functionMask);
148 const serialPortFunctionList_t *getSerialPortFunctionList(void);
150 void evaluateOtherData(uint8_t sr);
151 void handleSerial(void);