9 #define CRSF_TX_MODULE 1
10 #elif TARGET_RX || defined(UNIT_TEST)
11 #define CRSF_RX_MODULE 1
13 #error "Invalid configuration!"
17 #define PACKED __attribute__((packed))
19 #ifndef ICACHE_RAM_ATTR
20 #define ICACHE_RAM_ATTR
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 CRSF_PAYLOAD_SIZE_MAX 62
35 #define CRSF_FRAME_NOT_COUNTED_BYTES 2
36 #define CRSF_FRAME_SIZE(payload_size) ((payload_size) + 2) // See crsf_header_t.frame_size
37 #define CRSF_EXT_FRAME_SIZE(payload_size) (CRSF_FRAME_SIZE(payload_size) + 2)
38 #define CRSF_FRAME_SIZE_MAX (CRSF_PAYLOAD_SIZE_MAX + CRSF_FRAME_NOT_COUNTED_BYTES)
39 #define CRSF_FRAME_CRC_SIZE 1
40 #define CRSF_FRAME_LENGTH_EXT_TYPE_CRC 4 // length of Extended Dest/Origin, TYPE and CRC fields combined
42 #define CRSF_TELEMETRY_LENGTH_INDEX 1
43 #define CRSF_TELEMETRY_TYPE_INDEX 2
44 #define CRSF_TELEMETRY_FIELD_ID_INDEX 5
45 #define CRSF_TELEMETRY_FIELD_CHUNK_INDEX 6
46 #define CRSF_TELEMETRY_CRC_LENGTH 1
47 #define CRSF_TELEMETRY_TOTAL_SIZE(x) (x + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
49 //////////////////////////////////////////////////////////////
51 #define CRSF_MSP_REQ_PAYLOAD_SIZE 8
52 #define CRSF_MSP_RESP_PAYLOAD_SIZE 58
53 #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)
55 typedef enum : uint8_t
57 CRSF_FRAMETYPE_GPS
= 0x02,
58 CRSF_FRAMETYPE_VARIO
= 0x07,
59 CRSF_FRAMETYPE_BATTERY_SENSOR
= 0x08,
60 CRSF_FRAMETYPE_BARO_ALTITUDE
= 0x09,
61 CRSF_FRAMETYPE_LINK_STATISTICS
= 0x14,
62 CRSF_FRAMETYPE_OPENTX_SYNC
= 0x10,
63 CRSF_FRAMETYPE_RADIO_ID
= 0x3A,
64 CRSF_FRAMETYPE_RC_CHANNELS_PACKED
= 0x16,
65 CRSF_FRAMETYPE_ATTITUDE
= 0x1E,
66 CRSF_FRAMETYPE_FLIGHT_MODE
= 0x21,
67 // Extended Header Frames, range: 0x28 to 0x96
68 CRSF_FRAMETYPE_DEVICE_PING
= 0x28,
69 CRSF_FRAMETYPE_DEVICE_INFO
= 0x29,
70 CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY
= 0x2B,
71 CRSF_FRAMETYPE_PARAMETER_READ
= 0x2C,
72 CRSF_FRAMETYPE_PARAMETER_WRITE
= 0x2D,
74 //CRSF_FRAMETYPE_ELRS_STATUS = 0x2E, ELRS good/bad packet count and status flags
76 CRSF_FRAMETYPE_COMMAND
= 0x32,
78 CRSF_FRAMETYPE_KISS_REQ
= 0x78,
79 CRSF_FRAMETYPE_KISS_RESP
= 0x79,
81 CRSF_FRAMETYPE_MSP_REQ
= 0x7A, // response request using msp sequence as command
82 CRSF_FRAMETYPE_MSP_RESP
= 0x7B, // reply with 58 byte chunked binary
83 CRSF_FRAMETYPE_MSP_WRITE
= 0x7C, // write with 8 byte chunked binary (OpenTX outbound telemetry buffer limit)
85 CRSF_FRAMETYPE_ARDUPILOT_RESP
= 0x80,
88 typedef enum : uint8_t {
89 CRSF_COMMAND_SUBCMD_RX
= 0x10
92 typedef enum : uint8_t {
93 CRSF_COMMAND_SUBCMD_RX_BIND
= 0x01,
94 CRSF_COMMAND_MODEL_SELECT_ID
= 0x05
98 CRSF_FRAME_TX_MSP_FRAME_SIZE
= 58,
99 CRSF_FRAME_RX_MSP_FRAME_SIZE
= 8,
100 CRSF_FRAME_ORIGIN_DEST_SIZE
= 2,
104 CRSF_FRAME_GPS_PAYLOAD_SIZE
= 15,
105 CRSF_FRAME_VARIO_PAYLOAD_SIZE
= 2,
106 CRSF_FRAME_BARO_ALTITUDE_PAYLOAD_SIZE
= 4, // TBS version is 2, ELRS is 4 (combines vario)
107 CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE
= 8,
108 CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE
= 6,
109 CRSF_FRAME_DEVICE_INFO_PAYLOAD_SIZE
= 48,
110 CRSF_FRAME_FLIGHT_MODE_PAYLOAD_SIZE
= 16,
111 CRSF_FRAME_GENERAL_RESP_PAYLOAD_SIZE
= CRSF_EXT_FRAME_SIZE(CRSF_FRAME_TX_MSP_FRAME_SIZE
)
114 typedef enum : uint8_t
116 CRSF_ADDRESS_BROADCAST
= 0x00,
117 CRSF_ADDRESS_USB
= 0x10,
118 CRSF_ADDRESS_TBS_CORE_PNP_PRO
= 0x80,
119 CRSF_ADDRESS_RESERVED1
= 0x8A,
120 CRSF_ADDRESS_CURRENT_SENSOR
= 0xC0,
121 CRSF_ADDRESS_GPS
= 0xC2,
122 CRSF_ADDRESS_TBS_BLACKBOX
= 0xC4,
123 CRSF_ADDRESS_FLIGHT_CONTROLLER
= 0xC8,
124 CRSF_ADDRESS_RESERVED2
= 0xCA,
125 CRSF_ADDRESS_RACE_TAG
= 0xCC,
126 CRSF_ADDRESS_RADIO_TRANSMITTER
= 0xEA,
127 CRSF_ADDRESS_CRSF_RECEIVER
= 0xEC,
128 CRSF_ADDRESS_CRSF_TRANSMITTER
= 0xEE,
129 CRSF_ADDRESS_ELRS_LUA
= 0xEF
132 //typedef struct crsf_addr_e asas;
134 typedef enum : uint8_t
145 CRSF_TEXT_SELECTION
= 9,
151 CRSF_OUT_OF_RANGE
= 127,
154 // These flags are or'ed with the field type above to hide the field from the normal LUA view
155 #define CRSF_FIELD_HIDDEN 0x80 // marked as hidden in all LUA responses
156 #define CRSF_FIELD_ELRS_HIDDEN 0x40 // marked as hidden when talking to ELRS specific LUA
157 #define CRSF_FIELD_TYPE_MASK ~(CRSF_FIELD_HIDDEN|CRSF_FIELD_ELRS_HIDDEN)
160 * Define the shape of a standard header
162 typedef struct crsf_header_s
164 uint8_t device_addr
; // from crsf_addr_e
165 uint8_t frame_size
; // counts size after this byte, so it must be the payload size + 2 (type and crc)
166 crsf_frame_type_e type
;
167 } PACKED crsf_header_t
;
169 #define CRSF_MK_FRAME_T(payload) struct payload##_frame_s { crsf_header_t h; payload p; uint8_t crc; } PACKED
171 // Used by extended header frames (type in range 0x28 to 0x96)
172 typedef struct crsf_ext_header_s
174 // Common header fields, see crsf_header_t
177 crsf_frame_type_e type
;
179 crsf_addr_e dest_addr
;
180 crsf_addr_e orig_addr
;
182 } PACKED crsf_ext_header_t
;
185 * Crossfire packed channel structure, each channel is 11 bits
187 typedef struct crsf_channels_s
205 } PACKED crsf_channels_t
;
208 * Define the shape of a standard packet
209 * A 'standard' header followed by the packed channels
211 typedef struct rcPacket_s
213 crsf_header_t header
;
214 crsf_channels_s channels
;
217 typedef struct deviceInformationPacket_s
220 uint32_t hardwareVer
;
221 uint32_t softwareVer
;
222 uint8_t fieldCnt
; //number of field of params this device has
223 uint8_t parameterVersion
;
224 } PACKED deviceInformationPacket_t
;
226 #define DEVICE_INFORMATION_PAYLOAD_LENGTH (sizeof(deviceInformationPacket_t) + strlen(device_name)+1)
227 #define DEVICE_INFORMATION_LENGTH (sizeof(crsf_ext_header_t) + DEVICE_INFORMATION_PAYLOAD_LENGTH + CRSF_FRAME_CRC_SIZE)
228 #define DEVICE_INFORMATION_FRAME_SIZE (DEVICE_INFORMATION_PAYLOAD_LENGTH + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
230 // https://github.com/betaflight/betaflight/blob/master/src/main/msp/msp.c#L1949
231 typedef struct mspVtxConfigPacket_s
239 uint8_t deviceIsReady
;
240 uint8_t lowPowerDisarm
;
241 uint16_t pitModeFreq
;
242 uint8_t vtxTableAvailable
;
246 } PACKED mspVtxConfigPacket_t
;
248 typedef struct mspVtxPowerLevelPacket_s
252 uint8_t powerLabelLength
;
254 } PACKED mspVtxPowerLevelPacket_t
;
256 typedef struct mspVtxBandPacket_s
259 uint8_t bandNameLength
;
262 uint8_t isFactoryBand
;
265 } PACKED mspVtxBandPacket_t
;
267 #define MSP_REQUEST_PAYLOAD_LENGTH(len) 7 + len // status + flags + 2 function + 2 length + crc + payload
268 #define MSP_REQUEST_LENGTH(len) (sizeof(crsf_ext_header_t) + MSP_REQUEST_PAYLOAD_LENGTH(len) + CRSF_FRAME_CRC_SIZE)
269 #define MSP_REQUEST_FRAME_SIZE(len) (MSP_REQUEST_PAYLOAD_LENGTH(len) + CRSF_FRAME_LENGTH_EXT_TYPE_CRC)
271 #define MSP_SET_VTX_CONFIG_PAYLOAD_LENGTH 15
272 #define MSP_SET_VTXTABLE_BAND_PAYLOAD_LENGTH 29
273 #define MSP_SET_VTXTABLE_POWERLEVEL_PAYLOAD_LENGTH 7
275 * Union to allow accessing the input buffer as different data shapes
276 * without generating compiler warnings (and relying on undefined C++ behaviour!)
277 * Each entry in the union provides a different view of the same memory.
278 * This is just the defintion of the union, the declaration of the variable that
279 * uses it is later in the file.
283 uint8_t asUint8_t
[CRSF_MAX_PACKET_LEN
]; // max 64 bytes for CRSF packet serial buffer
284 rcPacket_t asRCPacket_t
; // access the memory as RC data
285 // add other packet types here
288 //CRSF_FRAMETYPE_BATTERY_SENSOR
289 typedef struct crsf_sensor_battery_s
291 unsigned voltage
: 16; // mv * 100 BigEndian
292 unsigned current
: 16; // ma * 100
293 unsigned capacity
: 24; // mah
294 unsigned remaining
: 8; // %
295 } PACKED crsf_sensor_battery_t
;
297 // CRSF_FRAMETYPE_BARO_ALTITUDE
298 typedef struct crsf_sensor_baro_vario_s
300 uint16_t altitude
; // Altitude in decimeters + 10000dm, or Altitude in meters if high bit is set, BigEndian
301 int16_t verticalspd
; // Vertical speed in cm/s, BigEndian
302 } PACKED crsf_sensor_baro_vario_t
;
304 // CRSF_FRAMETYPE_VARIO
305 typedef struct crsf_sensor_vario_s
307 int16_t verticalspd
; // Vertical speed in cm/s, BigEndian
308 } PACKED crsf_sensor_vario_t
;
310 // CRSF_FRAMETYPE_GPS
311 typedef struct crsf_sensor_gps_s
313 int32_t latitude
; // degree / 10`000`000
314 int32_t longitude
; // degree / 10`000`000
315 uint16_t groundspeed
; // km/h / 10
316 uint16_t gps_heading
; // degree / 100
317 uint16_t altitude
; // meter 1000m offset
318 uint8_t satellites_in_use
; // counter
319 } PACKED crsf_sensor_gps_t
;
321 // CRSF_FRAMETYPE_ATTITUDE
322 typedef struct crsf_sensor_attitude_s
324 int16_t pitch
; // radians * 10000
325 int16_t roll
; // radians * 10000
326 int16_t yaw
; // radians * 10000
327 } PACKED crsf_sensor_attitude_t
;
329 // CRSF_FRAMETYPE_FLIGHT_MODE
330 typedef struct crsf_sensor_flight_mode_s
332 char flight_mode
[16];
333 } PACKED crsf_flight_mode_t
;
336 * 0x14 Link statistics
339 * uint8_t Uplink RSSI Ant. 1 ( dBm * -1 )
340 * uint8_t Uplink RSSI Ant. 2 ( dBm * -1 )
341 * uint8_t Uplink Package success rate / Link quality ( % )
342 * int8_t Uplink SNR ( db )
343 * uint8_t Diversity active antenna ( enum ant. 1 = 0, ant. 2 )
344 * uint8_t RF Mode ( enum 4fps = 0 , 50fps, 150hz)
345 * uint8_t Uplink TX Power ( enum 0mW = 0, 10mW, 25 mW, 100 mW, 500 mW, 1000 mW, 2000mW )
346 * uint8_t Downlink RSSI ( dBm * -1 )
347 * uint8_t Downlink package success rate / Link quality ( % )
348 * int8_t Downlink SNR ( db )
349 * Uplink is the connection from the ground to the UAV and downlink the opposite direction.
352 typedef struct crsfPayloadLinkstatistics_s
354 uint8_t uplink_RSSI_1
;
355 uint8_t uplink_RSSI_2
;
356 uint8_t uplink_Link_quality
;
358 uint8_t active_antenna
;
360 uint8_t uplink_TX_Power
;
361 uint8_t downlink_RSSI_1
;
362 uint8_t downlink_Link_quality
;
364 } PACKED crsfLinkStatistics_t
;
366 typedef struct elrsLinkStatistics_s
: crsfLinkStatistics_t
368 uint8_t downlink_RSSI_2
;
369 } PACKED elrsLinkStatistics_t
;
371 // typedef struct crsfOpenTXsyncFrame_s
373 // uint32_t adjustedRefreshRate;
374 // uint32_t lastUpdate;
375 // uint16_t refreshRate;
376 // int8_t refreshRate;
377 // uint16_t inputLag;
380 // uint8_t downlink_RSSI;
381 // uint8_t downlink_Link_quality;
382 // int8_t downlink_SNR;
383 // } crsfOpenTXsyncFrame_t;
385 // typedef struct crsfOpenTXsyncFrame_s crsfOpenTXsyncFrame_t;
387 /////inline and utility functions//////
389 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
)
391 return ((x
- in_min
) * (out_max
- out_min
) * 2 / (in_max
- in_min
) + out_min
* 2 + 1) / 2;
394 // Scale a -100& to +100% crossfire value to 988-2012 (Taranis channel uS)
395 static inline uint16_t ICACHE_RAM_ATTR
CRSF_to_US(uint16_t val
)
397 return fmap(val
, CRSF_CHANNEL_VALUE_MIN
, CRSF_CHANNEL_VALUE_MAX
, 988, 2012);
400 // Scale down a 10-bit value to a -100& to +100% crossfire value
401 static inline uint16_t ICACHE_RAM_ATTR
UINT10_to_CRSF(uint16_t val
)
403 return fmap(val
, 0, 1023, CRSF_CHANNEL_VALUE_MIN
, CRSF_CHANNEL_VALUE_MAX
);
406 // Scale up a -100& to +100% crossfire value to 10-bit
407 static inline uint16_t ICACHE_RAM_ATTR
CRSF_to_UINT10(uint16_t val
)
409 return fmap(val
, CRSF_CHANNEL_VALUE_MIN
, CRSF_CHANNEL_VALUE_MAX
, 0, 1023);
412 // Convert 0-max to the CRSF values for 1000-2000
413 static inline uint16_t ICACHE_RAM_ATTR
N_to_CRSF(uint16_t val
, uint16_t max
)
415 return val
* (CRSF_CHANNEL_VALUE_2000
-CRSF_CHANNEL_VALUE_1000
) / max
+ CRSF_CHANNEL_VALUE_1000
;
418 // Convert CRSF to 0-(cnt-1), constrained between 1000us and 2000us
419 static inline uint16_t ICACHE_RAM_ATTR
CRSF_to_N(uint16_t val
, uint16_t cnt
)
421 // The span is increased by one to prevent the max val from returning cnt
422 if (val
<= CRSF_CHANNEL_VALUE_1000
)
424 if (val
>= CRSF_CHANNEL_VALUE_2000
)
426 return (val
- CRSF_CHANNEL_VALUE_1000
) * cnt
/ (CRSF_CHANNEL_VALUE_2000
- CRSF_CHANNEL_VALUE_1000
+ 1);
429 static inline uint8_t ICACHE_RAM_ATTR
CRSF_to_SWITCH3b(uint16_t ch
)
431 // AUX2-7 are Low Resolution, "7pos" 6+center (3-bit)
432 // The output is mapped evenly across 6 output values (0-5)
433 // with a special value 7 indicating the middle so it works
434 // with switches with a middle position as well as 6-position
435 const uint16_t CHANNEL_BIN_COUNT
= 6;
436 const uint16_t CHANNEL_BIN_SIZE
= (CRSF_CHANNEL_VALUE_MAX
- CRSF_CHANNEL_VALUE_MIN
) / CHANNEL_BIN_COUNT
;
437 // If channel is within 1/4 a BIN of being in the middle use special value 7
438 if (ch
< (CRSF_CHANNEL_VALUE_MID
-CHANNEL_BIN_SIZE
/4)
439 || ch
> (CRSF_CHANNEL_VALUE_MID
+CHANNEL_BIN_SIZE
/4))
440 return CRSF_to_N(ch
, CHANNEL_BIN_COUNT
);
444 // 3b switches use 0-5 to represent 6 positions switches and "7" to represent middle
445 // The calculation is a bit non-linear all the way to the endpoints due to where
446 // Ardupilot defines its modes
447 static inline uint16_t ICACHE_RAM_ATTR
SWITCH3b_to_CRSF(uint16_t val
)
451 case 0: return CRSF_CHANNEL_VALUE_1000
;
452 case 5: return CRSF_CHANNEL_VALUE_2000
;
453 case 6: // fallthrough
454 case 7: return CRSF_CHANNEL_VALUE_MID
;
455 default: // (val - 1) * 240 + 630; aka 150us spacing, starting at 1275
456 return val
* 240 + 391;
460 // Returns 1 if val is greater than CRSF_CHANNEL_VALUE_MID
461 static inline uint8_t ICACHE_RAM_ATTR
CRSF_to_BIT(uint16_t val
)
463 return (val
> CRSF_CHANNEL_VALUE_MID
) ? 1 : 0;
466 // Convert a bit into either the CRSF value for 1000 or 2000
467 static inline uint16_t ICACHE_RAM_ATTR
BIT_to_CRSF(uint8_t val
)
469 return (val
) ? CRSF_CHANNEL_VALUE_2000
: CRSF_CHANNEL_VALUE_1000
;
472 static inline uint8_t ICACHE_RAM_ATTR
CalcCRCMsp(uint8_t *data
, int length
)
475 for (uint8_t i
= 0; i
< length
; ++i
) {
481 #if !defined(__linux__)
482 static inline uint16_t htobe16(uint16_t val
)
484 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
487 return __builtin_bswap16(val
);
491 static inline uint16_t be16toh(uint16_t val
)
493 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
496 return __builtin_bswap16(val
);
500 static inline uint32_t htobe32(uint32_t val
)
502 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
505 return __builtin_bswap32(val
);
509 static inline uint32_t be32toh(uint32_t val
)
511 #if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
514 return __builtin_bswap32(val
);