include_v0.9/mavlink_types.h
Go to the documentation of this file.
1 #ifndef MAVLINK_TYPES_H_
2 #define MAVLINK_TYPES_H_
3 
4 #include "inttypes.h"
5 
7 {
18 };
19 
21 {
66 };
67 
69 {
80 };
81 
83 {
93 };
94 
95 enum MAV_NAV
96 {
107 };
108 
110 {
117  OCU = 6,
123 };
124 
126 {
132 };
133 
135 {
150 };
151 
153 {
159 };
160 
162 {
169 };
170 
171 #ifndef MAVLINK_MAX_PAYLOAD_LEN
172 // it is possible to override this, but be careful!
173 #define MAVLINK_MAX_PAYLOAD_LEN 255
174 #endif
175 
176 #define MAVLINK_CORE_HEADER_LEN 5
177 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1)
178 #define MAVLINK_NUM_CHECKSUM_BYTES 2
179 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
180 
181 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)
182 
183 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
184 #define MAVLINK_EXTENDED_HEADER_LEN 14
185 
186 #if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
187  /* full fledged 32bit++ OS */
188  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
189 #else
190  /* small microcontrollers */
191  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
192 #endif
193 
194 #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
195 
196 typedef struct param_union {
197  union {
198  float param_float;
199  int32_t param_int32;
200  uint32_t param_uint32;
201  uint8_t param_uint8;
202  uint8_t bytes[4];
203  };
204  uint8_t type;
206 
207 typedef struct __mavlink_system {
208  uint8_t sysid;
209  uint8_t compid;
210  uint8_t type;
211  uint8_t state;
212  uint8_t mode;
213  uint8_t nav_mode;
215 
216 typedef struct __mavlink_message {
217  uint16_t checksum;
218  uint8_t magic;
219  uint8_t len;
220  uint8_t seq;
221  uint8_t sysid;
222  uint8_t compid;
223  uint8_t msgid;
226 
227 
231  uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
233 
234 
235 typedef enum {
248 
249 #define MAVLINK_MAX_FIELDS 64
250 
251 typedef struct __mavlink_field_info {
252  const char *name; // name of this field
253  const char *print_format; // printing format hint, or NULL
254  mavlink_message_type_t type; // type of this field
255  unsigned int array_length; // if non-zero, field is an array
256  unsigned int wire_offset; // offset of each field in the payload
257  unsigned int structure_offset; // offset in a C structure
259 
260 // note that in this structure the order of fields is the order
261 // in the XML file, not necessary the wire order
262 typedef struct __mavlink_message_info {
263  const char *name; // name of the message
264  unsigned num_fields; // how many fields in this message
267 
268 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
269 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
270 
271 // checksum is immediately after the payload bytes
272 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
273 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
274 
275 typedef enum {
281 
282 /*
283  * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
284  * of buffers they will use. If more are used, then the result will be
285  * a stack overrun
286  */
287 #ifndef MAVLINK_COMM_NUM_BUFFERS
288 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
289 # define MAVLINK_COMM_NUM_BUFFERS 16
290 #else
291 # define MAVLINK_COMM_NUM_BUFFERS 4
292 #endif
293 #endif
294 
295 typedef enum {
307 
308 typedef struct __mavlink_status {
309  uint8_t msg_received;
310  uint8_t buffer_overrun;
311  uint8_t parse_error;
313  uint8_t packet_idx;
314  uint8_t current_rx_seq;
315  uint8_t current_tx_seq;
319 
320 #define MAVLINK_BIG_ENDIAN 0
321 #define MAVLINK_LITTLE_ENDIAN 1
322 
323 #endif /* MAVLINK_TYPES_H_ */


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:07