include_v2.0/mavlink_types.h
Go to the documentation of this file.
1 #pragma once
2 
3 // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
4 #if (defined _MSC_VER) && (_MSC_VER < 1600)
5 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
6 #endif
7 
8 #include <stdbool.h>
9 #include <stdint.h>
10 
11 #ifdef MAVLINK_USE_CXX_NAMESPACE
12 namespace mavlink {
13 #endif
14 
15 // Macro to define packed structures
16 #ifdef __GNUC__
17  #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
18 #else
19  #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
20 #endif
21 
22 #ifndef MAVLINK_MAX_PAYLOAD_LEN
23 // it is possible to override this, but be careful!
24 #define MAVLINK_MAX_PAYLOAD_LEN 255
25 #endif
26 
27 #define MAVLINK_CORE_HEADER_LEN 9
28 #define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5
29 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1)
30 #define MAVLINK_NUM_CHECKSUM_BYTES 2
31 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
32 
33 #define MAVLINK_SIGNATURE_BLOCK_LEN 13
34 
35 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN)
36 
37 
46 MAVPACKED(
47 typedef struct param_union {
48  union {
49  float param_float;
50  int32_t param_int32;
51  uint32_t param_uint32;
52  int16_t param_int16;
53  uint16_t param_uint16;
54  int8_t param_int8;
55  uint8_t param_uint8;
56  uint8_t bytes[4];
57  };
58  uint8_t type;
60 
61 
75 MAVPACKED(
76 typedef struct param_union_extended {
77  union {
78  struct {
79  uint8_t is_double:1;
80  uint8_t mavlink_type:7;
81  union {
82  char c;
83  uint8_t uint8;
84  int8_t int8;
85  uint16_t uint16;
86  int16_t int16;
87  uint32_t uint32;
88  int32_t int32;
89  float f;
90  uint8_t align[7];
91  };
92  };
93  uint8_t data[8];
94  };
95 }) mavlink_param_union_double_t;
96 
101 MAVPACKED(
102 typedef struct __mavlink_system {
103  uint8_t sysid;
104  uint8_t compid;
106 
107 MAVPACKED(
108 typedef struct __mavlink_message {
109  uint16_t checksum;
110  uint8_t magic;
111  uint8_t len;
112  uint8_t incompat_flags;
113  uint8_t compat_flags;
114  uint8_t seq;
115  uint8_t sysid;
116  uint8_t compid;
117  uint32_t msgid:24;
118  uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
119  uint8_t ck[2];
120  uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
122 
123 typedef enum {
136 
137 #define MAVLINK_MAX_FIELDS 64
138 
139 typedef struct __mavlink_field_info {
140  const char *name; // name of this field
141  const char *print_format; // printing format hint, or NULL
142  mavlink_message_type_t type; // type of this field
143  unsigned int array_length; // if non-zero, field is an array
144  unsigned int wire_offset; // offset of each field in the payload
145  unsigned int structure_offset; // offset in a C structure
147 
148 // note that in this structure the order of fields is the order
149 // in the XML file, not necessary the wire order
150 typedef struct __mavlink_message_info {
151  uint32_t msgid; // message ID
152  const char *name; // name of the message
153  unsigned num_fields; // how many fields in this message
154  mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
156 
157 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
158 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
159 
160 // checksum is immediately after the payload bytes
161 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
162 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
163 
164 typedef enum {
170 
171 /*
172  * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
173  * of buffers they will use. If more are used, then the result will be
174  * a stack overrun
175  */
176 #ifndef MAVLINK_COMM_NUM_BUFFERS
177 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
178 # define MAVLINK_COMM_NUM_BUFFERS 16
179 #else
180 # define MAVLINK_COMM_NUM_BUFFERS 4
181 #endif
182 #endif
183 
184 typedef enum {
202 
203 typedef enum {
209 
210 #define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1
211 #define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default
212 #define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated
213 #define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature
214 
215 #define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol
216 
217 typedef struct __mavlink_status {
218  uint8_t msg_received;
219  uint8_t buffer_overrun;
220  uint8_t parse_error;
221  mavlink_parse_state_t parse_state;
222  uint8_t packet_idx;
223  uint8_t current_rx_seq;
224  uint8_t current_tx_seq;
225  uint16_t packet_rx_success_count;
226  uint16_t packet_rx_drop_count;
227  uint8_t flags;
228  uint8_t signature_wait;
232 
233 /*
234  a callback function to allow for accepting unsigned packets
235  */
236 typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid);
237 
238 /*
239  flags controlling signing
240  */
241 #define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1
242 
243 /*
244  state of MAVLink signing for this channel
245  */
246 typedef struct __mavlink_signing {
247  uint8_t flags;
248  uint8_t link_id;
249  uint64_t timestamp;
250  uint8_t secret_key[32];
253 
254 /*
255  timestamp state of each logical signing stream. This needs to be the same structure for all
256  connections in order to be secure
257  */
258 #ifndef MAVLINK_MAX_SIGNING_STREAMS
259 #define MAVLINK_MAX_SIGNING_STREAMS 16
260 #endif
264  uint8_t link_id;
265  uint8_t sysid;
266  uint8_t compid;
267  uint8_t timestamp_bytes[6];
268  } stream[MAVLINK_MAX_SIGNING_STREAMS];
270 
271 
272 #define MAVLINK_BIG_ENDIAN 0
273 #define MAVLINK_LITTLE_ENDIAN 1
274 
275 #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1
276 #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2
277 
278 /*
279  entry in table of information about each message type
280  */
281 typedef struct __mavlink_msg_entry {
282  uint32_t msgid;
283  uint8_t crc_extra;
284  uint8_t msg_len;
285  uint8_t flags; // MAV_MSG_ENTRY_FLAG_*
286  uint8_t target_system_ofs; // payload offset to target_system, or 0
287  uint8_t target_component_ofs; // payload offset to target_component, or 0
289 
290 /*
291  incompat_flags bits
292  */
293 #define MAVLINK_IFLAG_SIGNED 0x01
294 #define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits
295 
296 #ifdef MAVLINK_USE_CXX_NAMESPACE
297 } // namespace mavlink
298 #endif
uint8_t target_component_ofs
uint8_t flags
uint8_t target_system_ofs
uint32_t msgid
uint8_t msg_len
uint8_t crc_extra


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02