mavlink_types.h
Go to the documentation of this file.
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
21 #endif
22 
23 #define MAVLINK_CORE_HEADER_LEN 5
24 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1)
25 #define MAVLINK_NUM_CHECKSUM_BYTES 2
26 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
27 
28 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)
29 
30 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
31 #define MAVLINK_EXTENDED_HEADER_LEN 14
32 
33 #if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)
34  /* full fledged 32bit++ OS */
35  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
36 #else
37  /* small microcontrollers */
38  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
39 #endif
40 
41 #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
42 
43 
53 MAVPACKED(
54 typedef struct param_union {
55  union {
56  float param_float;
57  int32_t param_int32;
58  uint32_t param_uint32;
59  int16_t param_int16;
60  uint16_t param_uint16;
61  int8_t param_int8;
62  uint8_t param_uint8;
63  uint8_t bytes[4];
64  };
65  uint8_t type;
66 }) mavlink_param_union_t;
67 
68 
82 MAVPACKED(
83 typedef struct param_union_extended {
84  union {
85  struct {
86  uint8_t is_double:1;
87  uint8_t mavlink_type:7;
88  union {
89  char c;
90  uint8_t uint8;
91  int8_t int8;
92  uint16_t uint16;
93  int16_t int16;
94  uint32_t uint32;
95  int32_t int32;
96  float f;
97  uint8_t align[7];
98  };
99  };
100  uint8_t data[8];
101  };
102 }) mavlink_param_union_double_t;
103 
108 MAVPACKED(
109 typedef struct __mavlink_system {
110  uint8_t sysid;
111  uint8_t compid;
112 }) mavlink_system_t;
113 
114 MAVPACKED(
115 typedef struct __mavlink_message {
116  uint16_t checksum;
117  uint8_t magic;
118  uint8_t len;
119  uint8_t seq;
120  uint8_t sysid;
121  uint8_t compid;
122  uint8_t msgid;
123  uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
124 }) mavlink_message_t;
125 
126 MAVPACKED(
127 typedef struct __mavlink_extended_message {
128  mavlink_message_t base_msg;
129  int32_t extended_payload_len;
130  uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
131 }) mavlink_extended_message_t;
132 
133 typedef enum {
146 
147 #define MAVLINK_MAX_FIELDS 64
148 
149 typedef struct __mavlink_field_info {
150  const char *name; // name of this field
151  const char *print_format; // printing format hint, or NULL
152  mavlink_message_type_t type; // type of this field
153  unsigned int array_length; // if non-zero, field is an array
154  unsigned int wire_offset; // offset of each field in the payload
155  unsigned int structure_offset; // offset in a C structure
157 
158 // note that in this structure the order of fields is the order
159 // in the XML file, not necessary the wire order
160 typedef struct __mavlink_message_info {
161  const char *name; // name of the message
162  unsigned num_fields; // how many fields in this message
163  mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
165 
166 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
167 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
168 
169 // checksum is immediately after the payload bytes
170 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
171 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
172 
173 typedef enum {
179 
180 /*
181  * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
182  * of buffers they will use. If more are used, then the result will be
183  * a stack overrun
184  */
185 #ifndef MAVLINK_COMM_NUM_BUFFERS
186 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
187 # define MAVLINK_COMM_NUM_BUFFERS 16
188 #else
189 # define MAVLINK_COMM_NUM_BUFFERS 4
190 #endif
191 #endif
192 
193 typedef enum {
206 
207 typedef enum {
212 
213 typedef struct __mavlink_status {
214  uint8_t msg_received;
215  uint8_t buffer_overrun;
216  uint8_t parse_error;
217  mavlink_parse_state_t parse_state;
218  uint8_t packet_idx;
219  uint8_t current_rx_seq;
220  uint8_t current_tx_seq;
224 
225 #define MAVLINK_BIG_ENDIAN 0
226 #define MAVLINK_LITTLE_ENDIAN 1
227 
228 #endif /* MAVLINK_TYPES_H_ */
static volatile uint8_t bytes
Definition: drv_i2c.c:97


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47