12#define PACKED __attribute__((packed))
14#define CRSF_BAUDRATE 420000
15#define CRSF_NUM_CHANNELS 16
16#define CRSF_CHANNEL_VALUE_MIN \
18#define CRSF_CHANNEL_VALUE_1000 191
19#define CRSF_CHANNEL_VALUE_MID 992
20#define CRSF_CHANNEL_VALUE_2000 1792
21#define CRSF_CHANNEL_VALUE_MAX \
23#define CRSF_CHANNEL_VALUE_SPAN \
24 (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN)
25#define CRSF_MAX_PACKET_SIZE \
27#define CRSF_MAX_PAYLOAD_LEN \
28 (CRSF_MAX_PACKET_SIZE - \
33 CRSF_FRAME_LENGTH_ADDRESS = 1,
34 CRSF_FRAME_LENGTH_FRAMELENGTH = 1,
35 CRSF_FRAME_LENGTH_TYPE = 1,
36 CRSF_FRAME_LENGTH_CRC = 1,
37 CRSF_FRAME_LENGTH_TYPE_CRC = 2,
38 CRSF_FRAME_LENGTH_EXT_TYPE_CRC =
40 CRSF_FRAME_LENGTH_NON_PAYLOAD =
46 CRSF_FRAME_GPS_PAYLOAD_SIZE = 15,
47 CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8,
48 CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10,
49 CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE =
51 CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
56 CRSF_FRAMETYPE_GPS = 0x02,
57 CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
58 CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
59 CRSF_FRAMETYPE_OPENTX_SYNC = 0x10,
60 CRSF_FRAMETYPE_RADIO_ID = 0x3A,
61 CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
62 CRSF_FRAMETYPE_ATTITUDE = 0x1E,
63 CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
65 CRSF_FRAMETYPE_DEVICE_PING = 0x28,
66 CRSF_FRAMETYPE_DEVICE_INFO = 0x29,
67 CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
68 CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
69 CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
70 CRSF_FRAMETYPE_COMMAND = 0x32,
72 CRSF_FRAMETYPE_MSP_REQ =
74 CRSF_FRAMETYPE_MSP_RESP = 0x7B,
75 CRSF_FRAMETYPE_MSP_WRITE = 0x7C,
81 CRSF_ADDRESS_BROADCAST = 0x00,
82 CRSF_ADDRESS_USB = 0x10,
83 CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
84 CRSF_ADDRESS_RESERVED1 = 0x8A,
85 CRSF_ADDRESS_CURRENT_SENSOR = 0xC0,
86 CRSF_ADDRESS_GPS = 0xC2,
87 CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
88 CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
89 CRSF_ADDRESS_RESERVED2 = 0xCA,
90 CRSF_ADDRESS_RACE_TAG = 0xCC,
91 CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
92 CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
93 CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE,
106 unsigned channel1 : 11;
107 unsigned channel2 : 11;
108 unsigned channel3 : 11;
109 unsigned channel4 : 11;
110 unsigned channel5 : 11;
111 unsigned channel6 : 11;
112 unsigned channel7 : 11;
113 unsigned channel8 : 11;
114 unsigned channel9 : 11;
115 unsigned channel10 : 11;
116 unsigned channel11 : 11;
117 unsigned channel12 : 11;
118 unsigned channel13 : 11;
119 unsigned channel14 : 11;
120 unsigned channel15 : 11;
121 unsigned channel16 : 11;
126 uint8_t uplink_RSSI_1;
127 uint8_t uplink_RSSI_2;
128 uint8_t uplink_Link_quality;
130 uint8_t active_antenna;
132 uint8_t uplink_TX_Power;
133 uint8_t downlink_RSSI;
134 uint8_t downlink_Link_quality;
140 uint32_t voltage : 16;
141 uint32_t current : 16;
142 uint32_t capacity : 24;
143 uint32_t remaining : 8;
150 uint16_t groundspeed;
156#if !defined(__linux__)
157static inline uint16_t htobe16(uint16_t val) {
158#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
161 return __builtin_bswap16(val);
165static inline uint16_t be16toh(uint16_t val) {
166#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
169 return __builtin_bswap16(val);
173static inline uint32_t htobe32(uint32_t val) {
174#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
177 return __builtin_bswap32(val);
181static inline uint32_t be32toh(uint32_t val) {
182#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
185 return __builtin_bswap32(val);
Definition crsf_protocol.h:125
Definition crsf_protocol.h:105
Definition crsf_protocol.h:139
Definition crsf_protocol.h:147