Dshot RPM Telemetry Refactoring (#13012)
[betaflight.git] / src / main / io / rcdevice.h
blob80e786f46253f7e0ec3d1edb5ef797510f94a949
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 "drivers/serial.h"
26 // The protocol for Runcam Device definition
28 #define RCDEVICE_PROTOCOL_HEADER 0xCC
30 #define RCDEVICE_PROTOCOL_MAX_PACKET_SIZE 64
31 #define RCDEVICE_PROTOCOL_MAX_DATA_SIZE 62
33 // Commands
34 #define RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO 0x00
35 // camera control
36 #define RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL 0x01
37 // 5 key osd cable simulation
38 #define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS 0x02
39 #define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE 0x03
40 #define RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION 0x04
41 #define RCDEVICE_PROTOCOL_COMMAND_REQUEST_FC_ATTITUDE 0x50
43 // Old protocol defines
44 #define RCSPLIT_PACKET_HEADER 0x55
45 #define RCSPLIT_PACKET_CMD_CTRL 0x01
46 #define RCSPLIT_PACKET_TAIL 0xaa
48 // Feature Flag sets, it's a uint16_t flag
49 typedef enum {
50 RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),
51 RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1),
52 RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE = (1 << 2),
53 RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE = (1 << 3),
54 RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),
55 RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),
56 RCDEVICE_PROTOCOL_FEATURE_CMS_MENU = (1 << 8),
57 RCDEVICE_PROTOCOL_FEATURE_FC_ATTITUDE = (1 << 9)
58 } rcdevice_features_e;
60 // Operation of Camera Button Simulation
61 typedef enum {
62 RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN = 0x00,
63 RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN = 0x01,
64 RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE = 0x02,
65 RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING = 0x03,
66 RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING = 0x04,
67 RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION = 0xFF
68 } rcdevice_camera_control_opeation_e;
70 // Operation Of 5 Key OSD Cable Simulation
71 typedef enum {
72 RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE = 0x00,
73 RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET = 0x01,
74 RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT = 0x02,
75 RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT = 0x03,
76 RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP = 0x04,
77 RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN = 0x05
78 } rcdevice_5key_simulation_operation_e;
80 // Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION
81 typedef enum {
82 RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01,
83 RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02
84 } RCDEVICE_5key_connection_event_e;
86 typedef enum {
87 RCDEVICE_CAM_KEY_NONE,
88 RCDEVICE_CAM_KEY_ENTER,
89 RCDEVICE_CAM_KEY_LEFT,
90 RCDEVICE_CAM_KEY_UP,
91 RCDEVICE_CAM_KEY_RIGHT,
92 RCDEVICE_CAM_KEY_DOWN,
93 RCDEVICE_CAM_KEY_CONNECTION_CLOSE,
94 RCDEVICE_CAM_KEY_CONNECTION_OPEN,
95 RCDEVICE_CAM_KEY_RELEASE,
96 } rcdeviceCamSimulationKeyEvent_e;
98 typedef enum {
99 RCDEVICE_PROTOCOL_RCSPLIT_VERSION = 0x00, // this is used to indicate the
100 // device that using rcsplit
101 // firmware version that <= 1.1.0
102 RCDEVICE_PROTOCOL_VERSION_1_0 = 0x01,
103 RCDEVICE_PROTOCOL_UNKNOWN
104 } rcdevice_protocol_version_e;
106 // end of Runcam Device definition
108 typedef struct runcamDeviceInfo_s {
109 rcdevice_protocol_version_e protocolVersion;
110 uint16_t features;
111 } runcamDeviceInfo_t;
113 typedef struct runcamDevice_s {
114 serialPort_t *serialPort;
115 uint8_t buffer[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
116 runcamDeviceInfo_t info;
117 bool isReady;
118 } runcamDevice_t;
120 #define MAX_WAITING_RESPONSES 1
122 typedef enum {
123 RCDEVICE_RESP_SUCCESS = 0,
124 RCDEVICE_RESP_INCORRECT_CRC = 1,
125 RCDEVICE_RESP_TIMEOUT = 2
126 } rcdeviceResponseStatus_e;
128 typedef struct rcdeviceResponseParseContext_s rcdeviceResponseParseContext_t;
129 typedef void(*rcdeviceRespParseFunc)(rcdeviceResponseParseContext_t*);
130 struct rcdeviceResponseParseContext_s {
131 uint8_t command;
132 uint8_t expectedRespLen; // total length of response data
133 uint8_t recvRespLen; // length of the data received
134 uint8_t *recvBuf; // response data buffer
135 timeMs_t timeout;
136 timeMs_t timeoutTimestamp; // if zero, it's means keep waiting for the response
137 rcdeviceRespParseFunc parserFunc;
138 runcamDevice_t *device;
139 uint8_t paramData[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
140 uint8_t paramDataLen;
141 uint8_t protocolVersion;
142 int maxRetryTimes;
143 void *userInfo;
144 rcdeviceResponseStatus_e result;
147 typedef struct {
148 uint8_t headPos; // current head position of the queue
149 uint8_t tailPos;
150 uint8_t itemCount; // the item count in the queue
151 rcdeviceResponseParseContext_t buffer[MAX_WAITING_RESPONSES];
152 rcdeviceRespParseFunc parseFunc;
153 } rcdeviceWaitingResponseQueue;
155 typedef struct {
156 uint8_t command;
157 uint8_t data[RCDEVICE_PROTOCOL_MAX_DATA_SIZE - 1];
158 uint8_t dataLength;
159 } runcamDeviceRequest_t;
161 void runcamDeviceInit(runcamDevice_t *device);
162 void rcdeviceReceive(timeUs_t currentTimeUs);
164 // camera button simulation
165 bool runcamDeviceSimulateCameraButton(runcamDevice_t *device, uint8_t operation);
167 // 5 key osd cable simulation
168 void runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
169 void runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
170 void runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation, rcdeviceRespParseFunc parseFunc);
171 void runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
173 void runcamDeviceSendAttitude(runcamDevice_t *device);
175 runcamDeviceRequest_t* rcdeviceGetRequest();