Merge pull request #10550 from etracer65/fix_serialportidentifier_enum
[betaflight.git] / src / main / io / serial.h
blobc49e27428fcf928f8d64c9b60d13dca335a30e0d
1 /*
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)
8 * any later version.
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/>.
21 #pragma once
23 #include <stdint.h>
24 #include <stdbool.h>
26 #include "pg/pg.h"
27 #include "drivers/serial.h"
29 typedef enum {
30 PORTSHARING_UNUSED = 0,
31 PORTSHARING_NOT_SHARED,
32 PORTSHARING_SHARED
33 } portSharing_e;
35 typedef enum {
36 FUNCTION_NONE = 0,
37 FUNCTION_MSP = (1 << 0), // 1
38 FUNCTION_GPS = (1 << 1), // 2
39 FUNCTION_TELEMETRY_FRSKY_HUB = (1 << 2), // 4
40 FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8
41 FUNCTION_TELEMETRY_LTM = (1 << 4), // 16
42 FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32
43 FUNCTION_RX_SERIAL = (1 << 6), // 64
44 FUNCTION_BLACKBOX = (1 << 7), // 128
45 FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
46 FUNCTION_ESC_SENSOR = (1 << 10), // 1024
47 FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048
48 FUNCTION_TELEMETRY_IBUS = (1 << 12), // 4096
49 FUNCTION_VTX_TRAMP = (1 << 13), // 8192
50 FUNCTION_RCDEVICE = (1 << 14), // 16384
51 FUNCTION_LIDAR_TF = (1 << 15), // 32768
52 FUNCTION_FRSKY_OSD = (1 << 16), // 65536
53 } serialPortFunction_e;
55 #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
56 #define TELEMETRY_PORT_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT)
58 typedef enum {
59 BAUD_AUTO = 0,
60 BAUD_9600,
61 BAUD_19200,
62 BAUD_38400,
63 BAUD_57600,
64 BAUD_115200,
65 BAUD_230400,
66 BAUD_250000,
67 BAUD_400000,
68 BAUD_460800,
69 BAUD_500000,
70 BAUD_921600,
71 BAUD_1000000,
72 BAUD_1500000,
73 BAUD_2000000,
74 BAUD_2470000
75 } baudRate_e;
77 extern const uint32_t baudRates[];
79 // serial port identifiers are now fixed, these values are used by MSP commands.
80 typedef enum {
81 SERIAL_PORT_ALL = -2,
82 SERIAL_PORT_NONE = -1,
83 SERIAL_PORT_USART1 = 0,
84 SERIAL_PORT_USART2,
85 SERIAL_PORT_USART3,
86 SERIAL_PORT_UART4,
87 SERIAL_PORT_UART5,
88 SERIAL_PORT_USART6,
89 SERIAL_PORT_USART7,
90 SERIAL_PORT_USART8,
91 SERIAL_PORT_LPUART1,
92 SERIAL_PORT_USB_VCP = 20,
93 SERIAL_PORT_SOFTSERIAL1 = 30,
94 SERIAL_PORT_SOFTSERIAL2,
95 SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2,
96 } serialPortIdentifier_e;
98 extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
100 #define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) < RESOURCE_SOFT_OFFSET) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
102 #define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) ((x) - SERIAL_PORT_USART1 + UARTDEV_1)
105 // runtime
107 typedef struct serialPortUsage_s {
108 serialPort_t *serialPort;
109 serialPortFunction_e function;
110 serialPortIdentifier_e identifier;
111 } serialPortUsage_t;
113 serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
116 // configuration
118 typedef struct serialPortConfig_s {
119 uint32_t functionMask;
120 serialPortIdentifier_e identifier;
121 uint8_t msp_baudrateIndex;
122 uint8_t gps_baudrateIndex;
123 uint8_t blackbox_baudrateIndex;
124 uint8_t telemetry_baudrateIndex; // not used for all telemetry systems, e.g. HoTT only works at 19200.
125 } serialPortConfig_t;
127 typedef struct serialConfig_s {
128 serialPortConfig_t portConfigs[SERIAL_PORT_COUNT];
129 uint16_t serial_update_rate_hz;
130 uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
131 } serialConfig_t;
133 PG_DECLARE(serialConfig_t, serialConfig);
135 typedef void serialConsumer(uint8_t);
138 // configuration
140 void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
141 void serialRemovePort(serialPortIdentifier_e identifier);
142 uint8_t serialGetAvailablePortCount(void);
143 bool serialIsPortAvailable(serialPortIdentifier_e identifier);
144 bool isSerialConfigValid(const serialConfig_t *serialConfig);
145 const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
146 serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier);
147 bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
148 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
149 const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
151 portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function);
152 bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
154 void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this
155 serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
156 int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier);
158 // runtime
160 serialPort_t *openSerialPort(
161 serialPortIdentifier_e identifier,
162 serialPortFunction_e function,
163 serialReceiveCallbackPtr rxCallback,
164 void *rxCallbackData,
165 uint32_t baudrate,
166 portMode_e mode,
167 portOptions_e options
169 void closeSerialPort(serialPort_t *serialPort);
171 void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
173 baudRate_e lookupBaudRateIndex(uint32_t baudRate);
177 // msp/cli/bootloader
179 void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC);