1 | #ifndef MAVLINK_TYPES_H_
|
---|
2 | #define MAVLINK_TYPES_H_
|
---|
3 |
|
---|
4 | // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
|
---|
5 | #if (defined _MSC_VER) && (_MSC_VER < 1600)
|
---|
6 | #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
|
---|
7 | #endif
|
---|
8 |
|
---|
9 | #include <stdint.h>
|
---|
10 |
|
---|
11 | // Macro to define packed structures
|
---|
12 | #ifdef __GNUC__
|
---|
13 | #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
|
---|
14 | #else
|
---|
15 | #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
|
---|
16 | #endif
|
---|
17 |
|
---|
18 | #ifndef MAVLINK_MAX_PAYLOAD_LEN
|
---|
19 | // it is possible to override this, but be careful!
|
---|
20 | #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
|
---|
21 | #endif
|
---|
22 |
|
---|
23 | #define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer)
|
---|
24 | #define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer)
|
---|
25 | #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx
|
---|
26 | #define MAVLINK_NUM_CHECKSUM_BYTES 2
|
---|
27 | #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
|
---|
28 |
|
---|
29 | #define MAVLINK_SIGNATURE_BLOCK_LEN 13
|
---|
30 |
|
---|
31 | #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length
|
---|
32 |
|
---|
33 | /**
|
---|
34 | * Old-style 4 byte param union
|
---|
35 | *
|
---|
36 | * This struct is the data format to be used when sending
|
---|
37 | * parameters. The parameter should be copied to the native
|
---|
38 | * type (without type conversion)
|
---|
39 | * and re-instanted on the receiving side using the
|
---|
40 | * native type as well.
|
---|
41 | */
|
---|
42 | MAVPACKED(
|
---|
43 | typedef struct param_union {
|
---|
44 | union {
|
---|
45 | float param_float;
|
---|
46 | int32_t param_int32;
|
---|
47 | uint32_t param_uint32;
|
---|
48 | int16_t param_int16;
|
---|
49 | uint16_t param_uint16;
|
---|
50 | int8_t param_int8;
|
---|
51 | uint8_t param_uint8;
|
---|
52 | uint8_t bytes[4];
|
---|
53 | };
|
---|
54 | uint8_t type;
|
---|
55 | }) mavlink_param_union_t;
|
---|
56 |
|
---|
57 |
|
---|
58 | /**
|
---|
59 | * New-style 8 byte param union
|
---|
60 | * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.
|
---|
61 | * The mavlink_param_union_double_t will be treated as a little-endian structure.
|
---|
62 | *
|
---|
63 | * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.
|
---|
64 | * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the
|
---|
65 | * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.
|
---|
66 | * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,
|
---|
67 | * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86,
|
---|
68 | * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
|
---|
69 | * and the bits pulled out using the shifts/masks.
|
---|
70 | */
|
---|
71 | MAVPACKED(
|
---|
72 | typedef struct param_union_extended {
|
---|
73 | union {
|
---|
74 | struct {
|
---|
75 | uint8_t is_double:1;
|
---|
76 | uint8_t mavlink_type:7;
|
---|
77 | union {
|
---|
78 | char c;
|
---|
79 | uint8_t uint8;
|
---|
80 | int8_t int8;
|
---|
81 | uint16_t uint16;
|
---|
82 | int16_t int16;
|
---|
83 | uint32_t uint32;
|
---|
84 | int32_t int32;
|
---|
85 | float f;
|
---|
86 | uint8_t align[7];
|
---|
87 | };
|
---|
88 | };
|
---|
89 | uint8_t data[8];
|
---|
90 | };
|
---|
91 | }) mavlink_param_union_double_t;
|
---|
92 |
|
---|
93 | /**
|
---|
94 | * This structure is required to make the mavlink_send_xxx convenience functions
|
---|
95 | * work, as it tells the library what the current system and component ID are.
|
---|
96 | */
|
---|
97 | MAVPACKED(
|
---|
98 | typedef struct __mavlink_system {
|
---|
99 | uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
|
---|
100 | uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
|
---|
101 | }) mavlink_system_t;
|
---|
102 |
|
---|
103 | MAVPACKED(
|
---|
104 | typedef struct __mavlink_message {
|
---|
105 | uint16_t checksum; ///< sent at end of packet
|
---|
106 | uint8_t magic; ///< protocol magic marker
|
---|
107 | uint8_t len; ///< Length of payload
|
---|
108 | uint8_t incompat_flags; ///< flags that must be understood
|
---|
109 | uint8_t compat_flags; ///< flags that can be ignored if not understood
|
---|
110 | uint8_t seq; ///< Sequence of packet
|
---|
111 | uint8_t sysid; ///< ID of message sender system/aircraft
|
---|
112 | uint8_t compid; ///< ID of the message sender component
|
---|
113 | uint32_t msgid:24; ///< ID of message in payload
|
---|
114 | uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
|
---|
115 | uint8_t ck[2]; ///< incoming checksum bytes
|
---|
116 | uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
|
---|
117 | }) mavlink_message_t;
|
---|
118 |
|
---|
119 | typedef enum {
|
---|
120 | MAVLINK_TYPE_CHAR = 0,
|
---|
121 | MAVLINK_TYPE_UINT8_T = 1,
|
---|
122 | MAVLINK_TYPE_INT8_T = 2,
|
---|
123 | MAVLINK_TYPE_UINT16_T = 3,
|
---|
124 | MAVLINK_TYPE_INT16_T = 4,
|
---|
125 | MAVLINK_TYPE_UINT32_T = 5,
|
---|
126 | MAVLINK_TYPE_INT32_T = 6,
|
---|
127 | MAVLINK_TYPE_UINT64_T = 7,
|
---|
128 | MAVLINK_TYPE_INT64_T = 8,
|
---|
129 | MAVLINK_TYPE_FLOAT = 9,
|
---|
130 | MAVLINK_TYPE_DOUBLE = 10
|
---|
131 | } mavlink_message_type_t;
|
---|
132 |
|
---|
133 | #define MAVLINK_MAX_FIELDS 64
|
---|
134 |
|
---|
135 | typedef struct __mavlink_field_info {
|
---|
136 | const char *name; // name of this field
|
---|
137 | const char *print_format; // printing format hint, or NULL
|
---|
138 | mavlink_message_type_t type; // type of this field
|
---|
139 | unsigned int array_length; // if non-zero, field is an array
|
---|
140 | unsigned int wire_offset; // offset of each field in the payload
|
---|
141 | unsigned int structure_offset; // offset in a C structure
|
---|
142 | } mavlink_field_info_t;
|
---|
143 |
|
---|
144 | // note that in this structure the order of fields is the order
|
---|
145 | // in the XML file, not necessary the wire order
|
---|
146 | typedef struct __mavlink_message_info {
|
---|
147 | uint32_t msgid; // message ID
|
---|
148 | const char *name; // name of the message
|
---|
149 | unsigned num_fields; // how many fields in this message
|
---|
150 | mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
---|
151 | } mavlink_message_info_t;
|
---|
152 |
|
---|
153 | #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
|
---|
154 | #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
|
---|
155 |
|
---|
156 | // checksum is immediately after the payload bytes
|
---|
157 | #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
---|
158 | #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
---|
159 |
|
---|
160 | typedef enum {
|
---|
161 | MAVLINK_COMM_0,
|
---|
162 | MAVLINK_COMM_1,
|
---|
163 | MAVLINK_COMM_2,
|
---|
164 | MAVLINK_COMM_3
|
---|
165 | } mavlink_channel_t;
|
---|
166 |
|
---|
167 | /*
|
---|
168 | * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
|
---|
169 | * of buffers they will use. If more are used, then the result will be
|
---|
170 | * a stack overrun
|
---|
171 | */
|
---|
172 | #ifndef MAVLINK_COMM_NUM_BUFFERS
|
---|
173 | #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
---|
174 | # define MAVLINK_COMM_NUM_BUFFERS 16
|
---|
175 | #else
|
---|
176 | # define MAVLINK_COMM_NUM_BUFFERS 4
|
---|
177 | #endif
|
---|
178 | #endif
|
---|
179 |
|
---|
180 | typedef enum {
|
---|
181 | MAVLINK_PARSE_STATE_UNINIT=0,
|
---|
182 | MAVLINK_PARSE_STATE_IDLE,
|
---|
183 | MAVLINK_PARSE_STATE_GOT_STX,
|
---|
184 | MAVLINK_PARSE_STATE_GOT_LENGTH,
|
---|
185 | MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS,
|
---|
186 | MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS,
|
---|
187 | MAVLINK_PARSE_STATE_GOT_SEQ,
|
---|
188 | MAVLINK_PARSE_STATE_GOT_SYSID,
|
---|
189 | MAVLINK_PARSE_STATE_GOT_COMPID,
|
---|
190 | MAVLINK_PARSE_STATE_GOT_MSGID1,
|
---|
191 | MAVLINK_PARSE_STATE_GOT_MSGID2,
|
---|
192 | MAVLINK_PARSE_STATE_GOT_MSGID3,
|
---|
193 | MAVLINK_PARSE_STATE_GOT_PAYLOAD,
|
---|
194 | MAVLINK_PARSE_STATE_GOT_CRC1,
|
---|
195 | MAVLINK_PARSE_STATE_GOT_BAD_CRC1,
|
---|
196 | MAVLINK_PARSE_STATE_SIGNATURE_WAIT
|
---|
197 | } mavlink_parse_state_t; ///< The state machine for the comm parser
|
---|
198 |
|
---|
199 | typedef enum {
|
---|
200 | MAVLINK_FRAMING_INCOMPLETE=0,
|
---|
201 | MAVLINK_FRAMING_OK=1,
|
---|
202 | MAVLINK_FRAMING_BAD_CRC=2,
|
---|
203 | MAVLINK_FRAMING_BAD_SIGNATURE=3
|
---|
204 | } mavlink_framing_t;
|
---|
205 |
|
---|
206 | #define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1
|
---|
207 | #define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default
|
---|
208 | #define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated
|
---|
209 | #define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature
|
---|
210 |
|
---|
211 | #define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol
|
---|
212 |
|
---|
213 | typedef struct __mavlink_status {
|
---|
214 | uint8_t msg_received; ///< Number of received messages
|
---|
215 | uint8_t buffer_overrun; ///< Number of buffer overruns
|
---|
216 | uint8_t parse_error; ///< Number of parse errors
|
---|
217 | mavlink_parse_state_t parse_state; ///< Parsing state machine
|
---|
218 | uint8_t packet_idx; ///< Index in current packet
|
---|
219 | uint8_t current_rx_seq; ///< Sequence number of last packet received
|
---|
220 | uint8_t current_tx_seq; ///< Sequence number of last packet sent
|
---|
221 | uint16_t packet_rx_success_count; ///< Received packets
|
---|
222 | uint16_t packet_rx_drop_count; ///< Number of packet drops
|
---|
223 | uint8_t flags; ///< MAVLINK_STATUS_FLAG_*
|
---|
224 | uint8_t signature_wait; ///< number of signature bytes left to receive
|
---|
225 | struct __mavlink_signing *signing; ///< optional signing state
|
---|
226 | struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps
|
---|
227 | } mavlink_status_t;
|
---|
228 |
|
---|
229 | /*
|
---|
230 | a callback function to allow for accepting unsigned packets
|
---|
231 | */
|
---|
232 | typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid);
|
---|
233 |
|
---|
234 | /*
|
---|
235 | flags controlling signing
|
---|
236 | */
|
---|
237 | #define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1
|
---|
238 |
|
---|
239 | /*
|
---|
240 | state of MAVLink signing for this channel
|
---|
241 | */
|
---|
242 | typedef struct __mavlink_signing {
|
---|
243 | uint8_t flags; ///< MAVLINK_SIGNING_FLAG_*
|
---|
244 | uint8_t link_id;
|
---|
245 | uint64_t timestamp;
|
---|
246 | uint8_t secret_key[32];
|
---|
247 | mavlink_accept_unsigned_t accept_unsigned_callback;
|
---|
248 | } mavlink_signing_t;
|
---|
249 |
|
---|
250 | /*
|
---|
251 | timestamp state of each logical signing stream. This needs to be the same structure for all
|
---|
252 | connections in order to be secure
|
---|
253 | */
|
---|
254 | #ifndef MAVLINK_MAX_SIGNING_STREAMS
|
---|
255 | #define MAVLINK_MAX_SIGNING_STREAMS 16
|
---|
256 | #endif
|
---|
257 | typedef struct __mavlink_signing_streams {
|
---|
258 | uint16_t num_signing_streams;
|
---|
259 | struct __mavlink_signing_stream {
|
---|
260 | uint8_t link_id;
|
---|
261 | uint8_t sysid;
|
---|
262 | uint8_t compid;
|
---|
263 | uint8_t timestamp_bytes[6];
|
---|
264 | } stream[MAVLINK_MAX_SIGNING_STREAMS];
|
---|
265 | } mavlink_signing_streams_t;
|
---|
266 |
|
---|
267 |
|
---|
268 | #define MAVLINK_BIG_ENDIAN 0
|
---|
269 | #define MAVLINK_LITTLE_ENDIAN 1
|
---|
270 |
|
---|
271 | #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1
|
---|
272 | #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2
|
---|
273 |
|
---|
274 | /*
|
---|
275 | entry in table of information about each message type
|
---|
276 | */
|
---|
277 | typedef struct __mavlink_msg_entry {
|
---|
278 | uint32_t msgid;
|
---|
279 | uint8_t crc_extra;
|
---|
280 | uint8_t msg_len;
|
---|
281 | uint8_t flags; // MAV_MSG_ENTRY_FLAG_*
|
---|
282 | uint8_t target_system_ofs; // payload offset to target_system, or 0
|
---|
283 | uint8_t target_component_ofs; // payload offset to target_component, or 0
|
---|
284 | } mavlink_msg_entry_t;
|
---|
285 |
|
---|
286 | /*
|
---|
287 | incompat_flags bits
|
---|
288 | */
|
---|
289 | #define MAVLINK_IFLAG_SIGNED 0x01
|
---|
290 | #define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits
|
---|
291 |
|
---|
292 | #endif /* MAVLINK_TYPES_H_ */
|
---|