Translate MAVLink telemetry to CRSF on the handset (rebased) (#2808)
[ExpressLRS.git] / src / lib / CrsfProtocol / crsf_protocol.h
blob5a4c080e853c9cdb6c5f70ee4c2957b6fdb7aa14
1 #pragma once
3 #include <cstdint>
4 #include <cmath>
5 #include "crc.h"
6 #include "options.h"
8 #if TARGET_TX
9 #define CRSF_TX_MODULE 1
10 #elif TARGET_RX || defined(UNIT_TEST)
11 #define CRSF_RX_MODULE 1
12 #else
13 #error "Invalid configuration!"
14 #endif
17 #define PACKED __attribute__((packed))
19 #ifndef ICACHE_RAM_ATTR
20 #define ICACHE_RAM_ATTR
21 #endif
23 #define CRSF_CRC_POLY 0xd5
25 #define CRSF_CHANNEL_VALUE_MIN 172 // 987us - actual CRSF min is 0 with E.Limits on
26 #define CRSF_CHANNEL_VALUE_1000 191
27 #define CRSF_CHANNEL_VALUE_MID 992
28 #define CRSF_CHANNEL_VALUE_2000 1792
29 #define CRSF_CHANNEL_VALUE_MAX 1811 // 2012us - actual CRSF max is 1984 with E.Limits on
30 #define CRSF_MAX_PACKET_LEN 64
32 #define CRSF_SYNC_BYTE 0xC8
34 #define RCframeLength 22 // length of the RC data packed bytes frame. 16 channels in 11 bits each.
35 #define LinkStatisticsFrameLength 10 //
36 #define OpenTXsyncFrameLength 11 //
37 #define BattSensorFrameLength 8 //
38 #define VTXcontrolFrameLength 12 //
40 #define CRSF_PAYLOAD_SIZE_MAX 62
41 #define CRSF_FRAME_NOT_COUNTED_BYTES 2
42 #define CRSF_FRAME_SIZE(payload_size) ((payload_size) + 2) // See crsf_header_t.frame_size
43 #define CRSF_EXT_FRAME_SIZE(payload_size) (CRSF_FRAME_SIZE(payload_size) + 2)
44 #define CRSF_FRAME_SIZE_MAX (CRSF_PAYLOAD_SIZE_MAX + CRSF_FRAME_NOT_COUNTED_BYTES)
45 #define CRSF_FRAME_CRC_SIZE 1
46 #define CRSF_FRAME_LENGTH_EXT_TYPE_CRC 4 // length of Extended Dest/Origin, TYPE and CRC fields combined
48 #define CRSF_TELEMETRY_LENGTH_INDEX 1
49 #define CRSF_TELEMETRY_TYPE_INDEX 2
50 #define CRSF_TELEMETRY_FIELD_ID_INDEX 5
51 #define CRSF_TELEMETRY_FIELD_CHUNK_INDEX 6
52 #define CRSF_TELEMETRY_CRC_LENGTH 1
53 #define CRSF_TELEMETRY_TOTAL_SIZE(x) (x + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
55 //////////////////////////////////////////////////////////////
57 #define CRSF_MSP_REQ_PAYLOAD_SIZE 8
58 #define CRSF_MSP_RESP_PAYLOAD_SIZE 58
59 #define CRSF_MSP_MAX_PAYLOAD_SIZE (CRSF_MSP_REQ_PAYLOAD_SIZE > CRSF_MSP_RESP_PAYLOAD_SIZE ? CRSF_MSP_REQ_PAYLOAD_SIZE : CRSF_MSP_RESP_PAYLOAD_SIZE)
61 typedef enum : uint8_t
63 CRSF_FRAMETYPE_GPS = 0x02,
64 CRSF_FRAMETYPE_VARIO = 0x07,
65 CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
66 CRSF_FRAMETYPE_BARO_ALTITUDE = 0x09,
67 CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
68 CRSF_FRAMETYPE_OPENTX_SYNC = 0x10,
69 CRSF_FRAMETYPE_RADIO_ID = 0x3A,
70 CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
71 CRSF_FRAMETYPE_ATTITUDE = 0x1E,
72 CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
73 // Extended Header Frames, range: 0x28 to 0x96
74 CRSF_FRAMETYPE_DEVICE_PING = 0x28,
75 CRSF_FRAMETYPE_DEVICE_INFO = 0x29,
76 CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
77 CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
78 CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
80 //CRSF_FRAMETYPE_ELRS_STATUS = 0x2E, ELRS good/bad packet count and status flags
82 CRSF_FRAMETYPE_COMMAND = 0x32,
83 // KISS frames
84 CRSF_FRAMETYPE_KISS_REQ = 0x78,
85 CRSF_FRAMETYPE_KISS_RESP = 0x79,
86 // MSP commands
87 CRSF_FRAMETYPE_MSP_REQ = 0x7A, // response request using msp sequence as command
88 CRSF_FRAMETYPE_MSP_RESP = 0x7B, // reply with 58 byte chunked binary
89 CRSF_FRAMETYPE_MSP_WRITE = 0x7C, // write with 8 byte chunked binary (OpenTX outbound telemetry buffer limit)
90 // Ardupilot frames
91 CRSF_FRAMETYPE_ARDUPILOT_RESP = 0x80,
92 } crsf_frame_type_e;
94 typedef enum : uint8_t {
95 CRSF_COMMAND_SUBCMD_RX = 0x10
96 } crsf_command_e;
98 typedef enum : uint8_t {
99 CRSF_COMMAND_SUBCMD_RX_BIND = 0x01,
100 CRSF_COMMAND_MODEL_SELECT_ID = 0x05
101 } crsf_subcommand_e;
103 enum {
104 CRSF_FRAME_TX_MSP_FRAME_SIZE = 58,
105 CRSF_FRAME_RX_MSP_FRAME_SIZE = 8,
106 CRSF_FRAME_ORIGIN_DEST_SIZE = 2,
109 enum {
110 CRSF_FRAME_GPS_PAYLOAD_SIZE = 15,
111 CRSF_FRAME_VARIO_PAYLOAD_SIZE = 2,
112 CRSF_FRAME_BARO_ALTITUDE_PAYLOAD_SIZE = 4, // TBS version is 2, ELRS is 4 (combines vario)
113 CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8,
114 CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
115 CRSF_FRAME_DEVICE_INFO_PAYLOAD_SIZE = 48,
116 CRSF_FRAME_FLIGHT_MODE_PAYLOAD_SIZE = 16,
117 CRSF_FRAME_GENERAL_RESP_PAYLOAD_SIZE = CRSF_EXT_FRAME_SIZE(CRSF_FRAME_TX_MSP_FRAME_SIZE)
120 typedef enum : uint8_t
122 CRSF_ADDRESS_BROADCAST = 0x00,
123 CRSF_ADDRESS_USB = 0x10,
124 CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
125 CRSF_ADDRESS_RESERVED1 = 0x8A,
126 CRSF_ADDRESS_CURRENT_SENSOR = 0xC0,
127 CRSF_ADDRESS_GPS = 0xC2,
128 CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
129 CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
130 CRSF_ADDRESS_RESERVED2 = 0xCA,
131 CRSF_ADDRESS_RACE_TAG = 0xCC,
132 CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
133 CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
134 CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE,
135 CRSF_ADDRESS_ELRS_LUA = 0xEF
136 } crsf_addr_e;
138 //typedef struct crsf_addr_e asas;
140 typedef enum : uint8_t
142 CRSF_UINT8 = 0,
143 CRSF_INT8 = 1,
144 CRSF_UINT16 = 2,
145 CRSF_INT16 = 3,
146 CRSF_UINT32 = 4,
147 CRSF_INT32 = 5,
148 CRSF_UINT64 = 6,
149 CRSF_INT64 = 7,
150 CRSF_FLOAT = 8,
151 CRSF_TEXT_SELECTION = 9,
152 CRSF_STRING = 10,
153 CRSF_FOLDER = 11,
154 CRSF_INFO = 12,
155 CRSF_COMMAND = 13,
156 CRSF_VTX = 15,
157 CRSF_OUT_OF_RANGE = 127,
158 } crsf_value_type_e;
160 // These flags are or'ed with the field type above to hide the field from the normal LUA view
161 #define CRSF_FIELD_HIDDEN 0x80 // marked as hidden in all LUA responses
162 #define CRSF_FIELD_ELRS_HIDDEN 0x40 // marked as hidden when talking to ELRS specific LUA
163 #define CRSF_FIELD_TYPE_MASK ~(CRSF_FIELD_HIDDEN|CRSF_FIELD_ELRS_HIDDEN)
166 * Define the shape of a standard header
168 typedef struct crsf_header_s
170 uint8_t device_addr; // from crsf_addr_e
171 uint8_t frame_size; // counts size after this byte, so it must be the payload size + 2 (type and crc)
172 crsf_frame_type_e type;
173 } PACKED crsf_header_t;
175 #define CRSF_MK_FRAME_T(payload) struct payload##_frame_s { crsf_header_t h; payload p; uint8_t crc; } PACKED
177 // Used by extended header frames (type in range 0x28 to 0x96)
178 typedef struct crsf_ext_header_s
180 // Common header fields, see crsf_header_t
181 uint8_t device_addr;
182 uint8_t frame_size;
183 crsf_frame_type_e type;
184 // Extended fields
185 crsf_addr_e dest_addr;
186 crsf_addr_e orig_addr;
187 uint8_t payload[0];
188 } PACKED crsf_ext_header_t;
191 * Crossfire packed channel structure, each channel is 11 bits
193 typedef struct crsf_channels_s
195 unsigned ch0 : 11;
196 unsigned ch1 : 11;
197 unsigned ch2 : 11;
198 unsigned ch3 : 11;
199 unsigned ch4 : 11;
200 unsigned ch5 : 11;
201 unsigned ch6 : 11;
202 unsigned ch7 : 11;
203 unsigned ch8 : 11;
204 unsigned ch9 : 11;
205 unsigned ch10 : 11;
206 unsigned ch11 : 11;
207 unsigned ch12 : 11;
208 unsigned ch13 : 11;
209 unsigned ch14 : 11;
210 unsigned ch15 : 11;
211 } PACKED crsf_channels_t;
214 * Define the shape of a standard packet
215 * A 'standard' header followed by the packed channels
217 typedef struct rcPacket_s
219 crsf_header_t header;
220 crsf_channels_s channels;
221 } PACKED rcPacket_t;
223 typedef struct deviceInformationPacket_s
225 uint32_t serialNo;
226 uint32_t hardwareVer;
227 uint32_t softwareVer;
228 uint8_t fieldCnt; //number of field of params this device has
229 uint8_t parameterVersion;
230 } PACKED deviceInformationPacket_t;
232 #define DEVICE_INFORMATION_PAYLOAD_LENGTH (sizeof(deviceInformationPacket_t) + strlen(device_name)+1)
233 #define DEVICE_INFORMATION_LENGTH (sizeof(crsf_ext_header_t) + DEVICE_INFORMATION_PAYLOAD_LENGTH + CRSF_FRAME_CRC_SIZE)
234 #define DEVICE_INFORMATION_FRAME_SIZE (DEVICE_INFORMATION_PAYLOAD_LENGTH + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
236 // https://github.com/betaflight/betaflight/blob/master/src/main/msp/msp.c#L1949
237 typedef struct mspVtxConfigPacket_s
239 uint8_t vtxType;
240 uint8_t band;
241 uint8_t channel;
242 uint8_t power;
243 uint8_t pitmode;
244 uint16_t freq;
245 uint8_t deviceIsReady;
246 uint8_t lowPowerDisarm;
247 uint16_t pitModeFreq;
248 uint8_t vtxTableAvailable;
249 uint8_t bands;
250 uint8_t channels;
251 uint8_t powerLevels;
252 } PACKED mspVtxConfigPacket_t;
254 typedef struct mspVtxPowerLevelPacket_s
256 uint8_t powerLevel;
257 uint16_t powerValue;
258 uint8_t powerLabelLength;
259 uint8_t label[3];
260 } PACKED mspVtxPowerLevelPacket_t;
262 typedef struct mspVtxBandPacket_s
264 uint8_t band;
265 uint8_t bandNameLength;
266 uint8_t bandName[8];
267 uint8_t bandLetter;
268 uint8_t isFactoryBand;
269 uint8_t channels;
270 uint16_t channel[8];
271 } PACKED mspVtxBandPacket_t;
273 #define MSP_REQUEST_PAYLOAD_LENGTH(len) 7 + len // status + flags + 2 function + 2 length + crc + payload
274 #define MSP_REQUEST_LENGTH(len) (sizeof(crsf_ext_header_t) + MSP_REQUEST_PAYLOAD_LENGTH(len) + CRSF_FRAME_CRC_SIZE)
275 #define MSP_REQUEST_FRAME_SIZE(len) (MSP_REQUEST_PAYLOAD_LENGTH(len) + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
277 #define MSP_SET_VTX_CONFIG_PAYLOAD_LENGTH 15
278 #define MSP_SET_VTXTABLE_BAND_PAYLOAD_LENGTH 29
279 #define MSP_SET_VTXTABLE_POWERLEVEL_PAYLOAD_LENGTH 7
281 * Union to allow accessing the input buffer as different data shapes
282 * without generating compiler warnings (and relying on undefined C++ behaviour!)
283 * Each entry in the union provides a different view of the same memory.
284 * This is just the defintion of the union, the declaration of the variable that
285 * uses it is later in the file.
287 union inBuffer_U
289 uint8_t asUint8_t[CRSF_MAX_PACKET_LEN]; // max 64 bytes for CRSF packet serial buffer
290 rcPacket_t asRCPacket_t; // access the memory as RC data
291 // add other packet types here
294 //CRSF_FRAMETYPE_BATTERY_SENSOR
295 typedef struct crsf_sensor_battery_s
297 unsigned voltage : 16; // mv * 100 BigEndian
298 unsigned current : 16; // ma * 100
299 unsigned capacity : 24; // mah
300 unsigned remaining : 8; // %
301 } PACKED crsf_sensor_battery_t;
303 // CRSF_FRAMETYPE_BARO_ALTITUDE
304 typedef struct crsf_sensor_baro_vario_s
306 uint16_t altitude; // Altitude in decimeters + 10000dm, or Altitude in meters if high bit is set, BigEndian
307 int16_t verticalspd; // Vertical speed in cm/s, BigEndian
308 } PACKED crsf_sensor_baro_vario_t;
310 // CRSF_FRAMETYPE_VARIO
311 typedef struct crsf_sensor_vario_s
313 int16_t verticalspd; // Vertical speed in cm/s, BigEndian
314 } PACKED crsf_sensor_vario_t;
316 // CRSF_FRAMETYPE_GPS
317 typedef struct crsf_sensor_gps_s
319 int32_t latitude; // degree / 10`000`000
320 int32_t longitude; // degree / 10`000`000
321 uint16_t groundspeed; // km/h / 10
322 uint16_t gps_heading; // degree / 100
323 uint16_t altitude; // meter ­1000m offset
324 uint8_t satellites_in_use; // counter
325 } PACKED crsf_sensor_gps_t;
327 // CRSF_FRAMETYPE_ATTITUDE
328 typedef struct crsf_sensor_attitude_s
330 int16_t pitch; // radians * 10000
331 int16_t roll; // radians * 10000
332 int16_t yaw; // radians * 10000
333 } PACKED crsf_sensor_attitude_t;
335 // CRSF_FRAMETYPE_FLIGHT_MODE
336 typedef struct crsf_sensor_flight_mode_s
338 char flight_mode[16];
339 } PACKED crsf_flight_mode_t;
342 * 0x14 Link statistics
343 * Payload:
345 * uint8_t Uplink RSSI Ant. 1 ( dBm * -1 )
346 * uint8_t Uplink RSSI Ant. 2 ( dBm * -1 )
347 * uint8_t Uplink Package success rate / Link quality ( % )
348 * int8_t Uplink SNR ( db )
349 * uint8_t Diversity active antenna ( enum ant. 1 = 0, ant. 2 )
350 * uint8_t RF Mode ( enum 4fps = 0 , 50fps, 150hz)
351 * uint8_t Uplink TX Power ( enum 0mW = 0, 10mW, 25 mW, 100 mW, 500 mW, 1000 mW, 2000mW )
352 * uint8_t Downlink RSSI ( dBm * -1 )
353 * uint8_t Downlink package success rate / Link quality ( % )
354 * int8_t Downlink SNR ( db )
355 * Uplink is the connection from the ground to the UAV and downlink the opposite direction.
358 typedef struct crsfPayloadLinkstatistics_s
360 uint8_t uplink_RSSI_1;
361 uint8_t uplink_RSSI_2;
362 uint8_t uplink_Link_quality;
363 int8_t uplink_SNR;
364 uint8_t active_antenna;
365 uint8_t rf_Mode;
366 uint8_t uplink_TX_Power;
367 uint8_t downlink_RSSI;
368 uint8_t downlink_Link_quality;
369 int8_t downlink_SNR;
370 } crsfLinkStatistics_t;
372 typedef struct crsfPayloadLinkstatistics_s crsfLinkStatistics_t;
374 // typedef struct crsfOpenTXsyncFrame_s
375 // {
376 // uint32_t adjustedRefreshRate;
377 // uint32_t lastUpdate;
378 // uint16_t refreshRate;
379 // int8_t refreshRate;
380 // uint16_t inputLag;
381 // uint8_t interval;
382 // uint8_t target;
383 // uint8_t downlink_RSSI;
384 // uint8_t downlink_Link_quality;
385 // int8_t downlink_SNR;
386 // } crsfOpenTXsyncFrame_t;
388 // typedef struct crsfOpenTXsyncFrame_s crsfOpenTXsyncFrame_t;
390 /////inline and utility functions//////
392 static uint16_t ICACHE_RAM_ATTR fmap(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max)
394 return ((x - in_min) * (out_max - out_min) * 2 / (in_max - in_min) + out_min * 2 + 1) / 2;
397 // Scale a -100& to +100% crossfire value to 988-2012 (Taranis channel uS)
398 static inline uint16_t ICACHE_RAM_ATTR CRSF_to_US(uint16_t val)
400 return fmap(val, CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX, 988, 2012);
403 // Scale down a 10-bit value to a -100& to +100% crossfire value
404 static inline uint16_t ICACHE_RAM_ATTR UINT10_to_CRSF(uint16_t val)
406 return fmap(val, 0, 1023, CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX);
409 // Scale up a -100& to +100% crossfire value to 10-bit
410 static inline uint16_t ICACHE_RAM_ATTR CRSF_to_UINT10(uint16_t val)
412 return fmap(val, CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX, 0, 1023);
415 // Convert 0-max to the CRSF values for 1000-2000
416 static inline uint16_t ICACHE_RAM_ATTR N_to_CRSF(uint16_t val, uint16_t max)
418 return val * (CRSF_CHANNEL_VALUE_2000-CRSF_CHANNEL_VALUE_1000) / max + CRSF_CHANNEL_VALUE_1000;
421 // Convert CRSF to 0-(cnt-1), constrained between 1000us and 2000us
422 static inline uint16_t ICACHE_RAM_ATTR CRSF_to_N(uint16_t val, uint16_t cnt)
424 // The span is increased by one to prevent the max val from returning cnt
425 if (val <= CRSF_CHANNEL_VALUE_1000)
426 return 0;
427 if (val >= CRSF_CHANNEL_VALUE_2000)
428 return cnt - 1;
429 return (val - CRSF_CHANNEL_VALUE_1000) * cnt / (CRSF_CHANNEL_VALUE_2000 - CRSF_CHANNEL_VALUE_1000 + 1);
432 static inline uint8_t ICACHE_RAM_ATTR CRSF_to_SWITCH3b(uint16_t ch)
434 // AUX2-7 are Low Resolution, "7pos" 6+center (3-bit)
435 // The output is mapped evenly across 6 output values (0-5)
436 // with a special value 7 indicating the middle so it works
437 // with switches with a middle position as well as 6-position
438 const uint16_t CHANNEL_BIN_COUNT = 6;
439 const uint16_t CHANNEL_BIN_SIZE = (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN) / CHANNEL_BIN_COUNT;
440 // If channel is within 1/4 a BIN of being in the middle use special value 7
441 if (ch < (CRSF_CHANNEL_VALUE_MID-CHANNEL_BIN_SIZE/4)
442 || ch > (CRSF_CHANNEL_VALUE_MID+CHANNEL_BIN_SIZE/4))
443 return CRSF_to_N(ch, CHANNEL_BIN_COUNT);
444 return 7;
447 // 3b switches use 0-5 to represent 6 positions switches and "7" to represent middle
448 // The calculation is a bit non-linear all the way to the endpoints due to where
449 // Ardupilot defines its modes
450 static inline uint16_t ICACHE_RAM_ATTR SWITCH3b_to_CRSF(uint16_t val)
452 switch (val)
454 case 0: return CRSF_CHANNEL_VALUE_1000;
455 case 5: return CRSF_CHANNEL_VALUE_2000;
456 case 6: // fallthrough
457 case 7: return CRSF_CHANNEL_VALUE_MID;
458 default: // (val - 1) * 240 + 630; aka 150us spacing, starting at 1275
459 return val * 240 + 391;
463 // Returns 1 if val is greater than CRSF_CHANNEL_VALUE_MID
464 static inline uint8_t ICACHE_RAM_ATTR CRSF_to_BIT(uint16_t val)
466 return (val > CRSF_CHANNEL_VALUE_MID) ? 1 : 0;
469 // Convert a bit into either the CRSF value for 1000 or 2000
470 static inline uint16_t ICACHE_RAM_ATTR BIT_to_CRSF(uint8_t val)
472 return (val) ? CRSF_CHANNEL_VALUE_2000 : CRSF_CHANNEL_VALUE_1000;
475 static inline uint8_t ICACHE_RAM_ATTR CalcCRCMsp(uint8_t *data, int length)
477 uint8_t crc = 0;
478 for (uint8_t i = 0; i < length; ++i) {
479 crc = crc ^ *data++;
481 return crc;
484 #if !defined(__linux__)
485 static inline uint16_t htobe16(uint16_t val)
487 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
488 return val;
489 #else
490 return __builtin_bswap16(val);
491 #endif
494 static inline uint16_t be16toh(uint16_t val)
496 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
497 return val;
498 #else
499 return __builtin_bswap16(val);
500 #endif
503 static inline uint32_t htobe32(uint32_t val)
505 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
506 return val;
507 #else
508 return __builtin_bswap32(val);
509 #endif
512 static inline uint32_t be32toh(uint32_t val)
514 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
515 return val;
516 #else
517 return __builtin_bswap32(val);
518 #endif
520 #endif