SerialIO
Loading...
Searching...
No Matches
crsf_protocol.h
1#pragma once
2
3#ifndef CRSF_PROTOCOL_H
4#define CRSF_PROTOCOL_H
5
6#ifdef __cplusplus
7extern "C" {
8#endif
9
10#include <stdint.h>
11
12#define PACKED __attribute__((packed))
13
14#define CRSF_BAUDRATE 420000
15#define CRSF_NUM_CHANNELS 16
16#define CRSF_CHANNEL_VALUE_MIN \
17 172
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 \
22 1811
23#define CRSF_CHANNEL_VALUE_SPAN \
24 (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN)
25#define CRSF_MAX_PACKET_SIZE \
26 64
27#define CRSF_MAX_PAYLOAD_LEN \
28 (CRSF_MAX_PACKET_SIZE - \
29 4)
30
32enum {
33 CRSF_FRAME_LENGTH_ADDRESS = 1, // length of ADDRESS field
34 CRSF_FRAME_LENGTH_FRAMELENGTH = 1, // length of FRAMELENGTH field
35 CRSF_FRAME_LENGTH_TYPE = 1, // length of TYPE field
36 CRSF_FRAME_LENGTH_CRC = 1, // length of CRC field
37 CRSF_FRAME_LENGTH_TYPE_CRC = 2, // length of TYPE and CRC fields combined
38 CRSF_FRAME_LENGTH_EXT_TYPE_CRC =
39 4, // length of Extended Dest/Origin, TYPE and CRC fields combined
40 CRSF_FRAME_LENGTH_NON_PAYLOAD =
41 4, // combined length of all fields except payload
42};
43
45enum {
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 =
50 22, // 11 bits per channel * 16 channels = 22 bytes.
51 CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
52};
53
55typedef enum {
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,
64 // Extended Header Frames, range: 0x28 to 0x96
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,
71 // MSP commands
72 CRSF_FRAMETYPE_MSP_REQ =
73 0x7A, // response request using msp sequence as command
74 CRSF_FRAMETYPE_MSP_RESP = 0x7B, // reply with 58 byte chunked binary
75 CRSF_FRAMETYPE_MSP_WRITE = 0x7C, // write with 8 byte chunked binary (OpenTX
76 // outbound telemetry_buffer limit)
77} crsf_frame_type_e;
78
80typedef enum {
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,
94} crsf_addr_e;
95
97typedef struct crsf_header_s {
98 uint8_t device_addr; // from crsf_addr_e
99 uint8_t frame_size; // counts size after this byte, so it must be the payload
100 // size + 2 (type and crc)
101 uint8_t type; // from crsf_frame_type_e
102} PACKED crsf_header_t;
103
105typedef struct crsf_channels_s {
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;
122} PACKED crsf_channels_t;
123
126 uint8_t uplink_RSSI_1;
127 uint8_t uplink_RSSI_2;
128 uint8_t uplink_Link_quality;
129 int8_t uplink_SNR;
130 uint8_t active_antenna;
131 uint8_t rf_Mode;
132 uint8_t uplink_TX_Power;
133 uint8_t downlink_RSSI;
134 uint8_t downlink_Link_quality;
135 int8_t downlink_SNR;
137
139typedef struct crsf_sensor_battery_s {
140 uint32_t voltage : 16; // V * 10 big endian
141 uint32_t current : 16; // A * 10 big endian
142 uint32_t capacity : 24; // mah big endian
143 uint32_t remaining : 8; // %
144} PACKED crsf_sensor_battery_t;
145
147typedef struct crsf_sensor_gps_s {
148 int32_t latitude; // degree / 10,000,000 big endian
149 int32_t longitude; // degree / 10,000,000 big endian
150 uint16_t groundspeed; // km/h / 10 big endian
151 uint16_t heading; // GPS heading, degree/100 big endian
152 uint16_t altitude; // meters, +1000m big endian
153 uint8_t satellites; // satellites
154} PACKED crsf_sensor_gps_t;
155
156#if !defined(__linux__)
157static inline uint16_t htobe16(uint16_t val) {
158#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
159 return val;
160#else
161 return __builtin_bswap16(val);
162#endif
163}
164
165static inline uint16_t be16toh(uint16_t val) {
166#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
167 return val;
168#else
169 return __builtin_bswap16(val);
170#endif
171}
172
173static inline uint32_t htobe32(uint32_t val) {
174#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
175 return val;
176#else
177 return __builtin_bswap32(val);
178#endif
179}
180
181static inline uint32_t be32toh(uint32_t val) {
182#if (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__)
183 return val;
184#else
185 return __builtin_bswap32(val);
186#endif
187}
188#endif
189
190#ifdef __cplusplus
191}
192#endif
193
194#endif // CRSF_PROTOCOL_H
Definition crsf_protocol.h:125
Definition crsf_protocol.h:105
Definition crsf_protocol.h:97
Definition crsf_protocol.h:139
Definition crsf_protocol.h:147