16#define PACKED __attribute__((packed))
18#define CRSF_BAUDRATE 420000
19#define CRSF_NUM_CHANNELS 16
20#define CRSF_CHANNEL_VALUE_MIN \
22#define CRSF_CHANNEL_VALUE_1000 191
23#define CRSF_CHANNEL_VALUE_MID 992
24#define CRSF_CHANNEL_VALUE_2000 1792
25#define CRSF_CHANNEL_VALUE_MAX \
27#define CRSF_CHANNEL_VALUE_SPAN \
28 (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN)
29#define CRSF_MAX_PACKET_SIZE \
31#define CRSF_MAX_PAYLOAD_LEN \
32 (CRSF_MAX_PACKET_SIZE - \
37 CRSF_FRAME_LENGTH_ADDRESS = 1,
38 CRSF_FRAME_LENGTH_FRAMELENGTH = 1,
39 CRSF_FRAME_LENGTH_TYPE = 1,
40 CRSF_FRAME_LENGTH_CRC = 1,
41 CRSF_FRAME_LENGTH_TYPE_CRC = 2,
42 CRSF_FRAME_LENGTH_EXT_TYPE_CRC =
44 CRSF_FRAME_LENGTH_NON_PAYLOAD =
50 CRSF_FRAME_GPS_PAYLOAD_SIZE = 15,
51 CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8,
52 CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10,
53 CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE =
55 CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
60 CRSF_FRAMETYPE_GPS = 0x02,
61 CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
62 CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
63 CRSF_FRAMETYPE_OPENTX_SYNC = 0x10,
64 CRSF_FRAMETYPE_RADIO_ID = 0x3A,
65 CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
66 CRSF_FRAMETYPE_ATTITUDE = 0x1E,
67 CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
69 CRSF_FRAMETYPE_DEVICE_PING = 0x28,
70 CRSF_FRAMETYPE_DEVICE_INFO = 0x29,
71 CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
72 CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
73 CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
74 CRSF_FRAMETYPE_COMMAND = 0x32,
76 CRSF_FRAMETYPE_MSP_REQ =
78 CRSF_FRAMETYPE_MSP_RESP = 0x7B,
79 CRSF_FRAMETYPE_MSP_WRITE = 0x7C,
85 CRSF_ADDRESS_BROADCAST = 0x00,
86 CRSF_ADDRESS_USB = 0x10,
87 CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
88 CRSF_ADDRESS_RESERVED1 = 0x8A,
89 CRSF_ADDRESS_CURRENT_SENSOR = 0xC0,
90 CRSF_ADDRESS_GPS = 0xC2,
91 CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
92 CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
93 CRSF_ADDRESS_RESERVED2 = 0xCA,
94 CRSF_ADDRESS_RACE_TAG = 0xCC,
95 CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
96 CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
97 CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE,
110 unsigned channel1 : 11;
111 unsigned channel2 : 11;
112 unsigned channel3 : 11;
113 unsigned channel4 : 11;
114 unsigned channel5 : 11;
115 unsigned channel6 : 11;
116 unsigned channel7 : 11;
117 unsigned channel8 : 11;
118 unsigned channel9 : 11;
119 unsigned channel10 : 11;
120 unsigned channel11 : 11;
121 unsigned channel12 : 11;
122 unsigned channel13 : 11;
123 unsigned channel14 : 11;
124 unsigned channel15 : 11;
125 unsigned channel16 : 11;
130 uint8_t uplink_RSSI_1;
131 uint8_t uplink_RSSI_2;
132 uint8_t uplink_Link_quality;
134 uint8_t active_antenna;
136 uint8_t uplink_TX_Power;
137 uint8_t downlink_RSSI;
138 uint8_t downlink_Link_quality;
144 uint32_t voltage : 16;
145 uint32_t current : 16;
146 uint32_t capacity : 24;
147 uint32_t remaining : 8;
154 uint16_t groundspeed;
160#if !defined(__linux__)
161static inline uint16_t htobe16(uint16_t val) {
162#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
165 return __builtin_bswap16(val);
169static inline uint16_t be16toh(uint16_t val) {
170#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
173 return __builtin_bswap16(val);
177static inline uint32_t htobe32(uint32_t val) {
178#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
181 return __builtin_bswap32(val);
185static inline uint32_t be32toh(uint32_t val) {
186#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
189 return __builtin_bswap32(val);
struct crsf_header_s crsf_header_t
struct crsf_sensor_battery_s crsf_sensor_battery_t
crsf_addr_e
Definition crsf_protocol.h:84
struct crsfPayloadLinkstatistics_s crsfLinkStatistics_t
crsf_frame_type_e
Definition crsf_protocol.h:59
struct crsf_channels_s crsf_channels_t
struct crsf_sensor_gps_s crsf_sensor_gps_t
Definition crsf_protocol.h:129
Definition crsf_protocol.h:109
Definition crsf_protocol.h:143
Definition crsf_protocol.h:151