Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | #ifndef MAVLINK_TYPES_H_ |
2 | #define MAVLINK_TYPES_H_ |
||
3 | |||
4 | #include <inttypes.h> |
||
5 | |||
6 | #ifndef MAVLINK_MAX_PAYLOAD_LEN |
||
7 | // it is possible to override this, but be careful! |
||
8 | #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length |
||
9 | #endif |
||
10 | |||
11 | #define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) |
||
12 | #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum |
||
13 | #define MAVLINK_NUM_CHECKSUM_BYTES 2 |
||
14 | #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) |
||
15 | |||
16 | #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length |
||
17 | |||
18 | #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 |
||
19 | #define MAVLINK_EXTENDED_HEADER_LEN 14 |
||
20 | |||
21 | #if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) |
||
22 | /* full fledged 32bit++ OS */ |
||
23 | #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 |
||
24 | #else |
||
25 | /* small microcontrollers */ |
||
26 | #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 |
||
27 | #endif |
||
28 | |||
29 | #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) |
||
30 | |||
31 | typedef struct param_union { |
||
32 | union { |
||
33 | float param_float; |
||
34 | int32_t param_int32; |
||
35 | uint32_t param_uint32; |
||
36 | uint8_t param_uint8; |
||
37 | uint8_t bytes[4]; |
||
38 | }; |
||
39 | uint8_t type; |
||
40 | } mavlink_param_union_t; |
||
41 | |||
42 | typedef struct __mavlink_system { |
||
43 | uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function |
||
44 | uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function |
||
45 | uint8_t type; ///< Unused, can be used by user to store the system's type |
||
46 | uint8_t state; ///< Unused, can be used by user to store the system's state |
||
47 | uint8_t mode; ///< Unused, can be used by user to store the system's mode |
||
48 | uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode |
||
49 | } mavlink_system_t; |
||
50 | |||
51 | typedef struct __mavlink_message { |
||
52 | uint16_t checksum; /// sent at end of packet |
||
53 | uint8_t magic; ///< protocol magic marker |
||
54 | uint8_t len; ///< Length of payload |
||
55 | uint8_t seq; ///< Sequence of packet |
||
56 | uint8_t sysid; ///< ID of message sender system/aircraft |
||
57 | uint8_t compid; ///< ID of the message sender component |
||
58 | uint8_t msgid; ///< ID of message in payload |
||
59 | uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; |
||
60 | } mavlink_message_t; |
||
61 | |||
62 | |||
63 | typedef struct __mavlink_extended_message { |
||
64 | mavlink_message_t base_msg; |
||
65 | int32_t extended_payload_len; ///< Length of extended payload if any |
||
66 | uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; |
||
67 | } mavlink_extended_message_t; |
||
68 | |||
69 | |||
70 | typedef enum { |
||
71 | MAVLINK_TYPE_CHAR = 0, |
||
72 | MAVLINK_TYPE_UINT8_T = 1, |
||
73 | MAVLINK_TYPE_INT8_T = 2, |
||
74 | MAVLINK_TYPE_UINT16_T = 3, |
||
75 | MAVLINK_TYPE_INT16_T = 4, |
||
76 | MAVLINK_TYPE_UINT32_T = 5, |
||
77 | MAVLINK_TYPE_INT32_T = 6, |
||
78 | MAVLINK_TYPE_UINT64_T = 7, |
||
79 | MAVLINK_TYPE_INT64_T = 8, |
||
80 | MAVLINK_TYPE_FLOAT = 9, |
||
81 | MAVLINK_TYPE_DOUBLE = 10 |
||
82 | } mavlink_message_type_t; |
||
83 | |||
84 | #define MAVLINK_MAX_FIELDS 64 |
||
85 | |||
86 | typedef struct __mavlink_field_info { |
||
87 | const char *name; // name of this field |
||
88 | const char *print_format; // printing format hint, or NULL |
||
89 | mavlink_message_type_t type; // type of this field |
||
90 | unsigned int array_length; // if non-zero, field is an array |
||
91 | unsigned int wire_offset; // offset of each field in the payload |
||
92 | unsigned int structure_offset; // offset in a C structure |
||
93 | } mavlink_field_info_t; |
||
94 | |||
95 | // note that in this structure the order of fields is the order |
||
96 | // in the XML file, not necessary the wire order |
||
97 | typedef struct __mavlink_message_info { |
||
98 | const char *name; // name of the message |
||
99 | unsigned num_fields; // how many fields in this message |
||
100 | mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information |
||
101 | } mavlink_message_info_t; |
||
102 | |||
103 | #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) |
||
104 | #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) |
||
105 | |||
106 | // checksum is immediately after the payload bytes |
||
107 | #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) |
||
108 | #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) |
||
109 | |||
110 | typedef enum { |
||
111 | MAVLINK_COMM_0, |
||
112 | MAVLINK_COMM_1, |
||
113 | MAVLINK_COMM_2, |
||
114 | MAVLINK_COMM_3 |
||
115 | } mavlink_channel_t; |
||
116 | |||
117 | /* |
||
118 | * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number |
||
119 | * of buffers they will use. If more are used, then the result will be |
||
120 | * a stack overrun |
||
121 | */ |
||
122 | #ifndef MAVLINK_COMM_NUM_BUFFERS |
||
123 | #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) |
||
124 | # define MAVLINK_COMM_NUM_BUFFERS 16 |
||
125 | #else |
||
126 | # define MAVLINK_COMM_NUM_BUFFERS 4 |
||
127 | #endif |
||
128 | #endif |
||
129 | |||
130 | typedef enum { |
||
131 | MAVLINK_PARSE_STATE_UNINIT=0, |
||
132 | MAVLINK_PARSE_STATE_IDLE, |
||
133 | MAVLINK_PARSE_STATE_GOT_STX, |
||
134 | MAVLINK_PARSE_STATE_GOT_SEQ, |
||
135 | MAVLINK_PARSE_STATE_GOT_LENGTH, |
||
136 | MAVLINK_PARSE_STATE_GOT_SYSID, |
||
137 | MAVLINK_PARSE_STATE_GOT_COMPID, |
||
138 | MAVLINK_PARSE_STATE_GOT_MSGID, |
||
139 | MAVLINK_PARSE_STATE_GOT_PAYLOAD, |
||
140 | MAVLINK_PARSE_STATE_GOT_CRC1 |
||
141 | } mavlink_parse_state_t; ///< The state machine for the comm parser |
||
142 | |||
143 | typedef struct __mavlink_status { |
||
144 | uint8_t msg_received; ///< Number of received messages |
||
145 | uint8_t buffer_overrun; ///< Number of buffer overruns |
||
146 | uint8_t parse_error; ///< Number of parse errors |
||
147 | mavlink_parse_state_t parse_state; ///< Parsing state machine |
||
148 | uint8_t packet_idx; ///< Index in current packet |
||
149 | uint8_t current_rx_seq; ///< Sequence number of last packet received |
||
150 | uint8_t current_tx_seq; ///< Sequence number of last packet sent |
||
151 | uint16_t packet_rx_success_count; ///< Received packets |
||
152 | uint16_t packet_rx_drop_count; ///< Number of packet drops |
||
153 | } mavlink_status_t; |
||
154 | |||
155 | #define MAVLINK_BIG_ENDIAN 0 |
||
156 | #define MAVLINK_LITTLE_ENDIAN 1 |
||
157 | |||
158 | #endif /* MAVLINK_TYPES_H_ */ |