Go to the documentation of this file.00001 #ifndef MAVLINK_TYPES_H_
00002 #define MAVLINK_TYPES_H_
00003
00004
00005 #if (defined _MSC_VER) && (_MSC_VER < 1600)
00006 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
00007 #endif
00008
00009 #include <stdint.h>
00010
00011
00012 #ifdef __GNUC__
00013 #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
00014 #else
00015 #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
00016 #endif
00017
00018 #ifndef MAVLINK_MAX_PAYLOAD_LEN
00019
00020 #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
00021 #endif
00022
00023 #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)
00024 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
00025 #define MAVLINK_NUM_CHECKSUM_BYTES 2
00026 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
00027
00028 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
00029
00030 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
00031 #define MAVLINK_EXTENDED_HEADER_LEN 14
00032
00033 #if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)
00034
00035 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
00036 #else
00037
00038 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
00039 #endif
00040
00041 #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
00042
00043
00053 MAVPACKED(
00054 typedef struct param_union {
00055 union {
00056 float param_float;
00057 int32_t param_int32;
00058 uint32_t param_uint32;
00059 int16_t param_int16;
00060 uint16_t param_uint16;
00061 int8_t param_int8;
00062 uint8_t param_uint8;
00063 uint8_t bytes[4];
00064 };
00065 uint8_t type;
00066 }) mavlink_param_union_t;
00067
00068
00082 MAVPACKED(
00083 typedef struct param_union_extended {
00084 union {
00085 struct {
00086 uint8_t is_double:1;
00087 uint8_t mavlink_type:7;
00088 union {
00089 char c;
00090 uint8_t uint8;
00091 int8_t int8;
00092 uint16_t uint16;
00093 int16_t int16;
00094 uint32_t uint32;
00095 int32_t int32;
00096 float f;
00097 uint8_t align[7];
00098 };
00099 };
00100 uint8_t data[8];
00101 };
00102 }) mavlink_param_union_double_t;
00103
00108 MAVPACKED(
00109 typedef struct __mavlink_system {
00110 uint8_t sysid;
00111 uint8_t compid;
00112 }) mavlink_system_t;
00113
00114 MAVPACKED(
00115 typedef struct __mavlink_message {
00116 uint16_t checksum;
00117 uint8_t magic;
00118 uint8_t len;
00119 uint8_t seq;
00120 uint8_t sysid;
00121 uint8_t compid;
00122 uint8_t msgid;
00123 uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
00124 }) mavlink_message_t;
00125
00126 MAVPACKED(
00127 typedef struct __mavlink_extended_message {
00128 mavlink_message_t base_msg;
00129 int32_t extended_payload_len;
00130 uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
00131 }) mavlink_extended_message_t;
00132
00133 typedef enum {
00134 MAVLINK_TYPE_CHAR = 0,
00135 MAVLINK_TYPE_UINT8_T = 1,
00136 MAVLINK_TYPE_INT8_T = 2,
00137 MAVLINK_TYPE_UINT16_T = 3,
00138 MAVLINK_TYPE_INT16_T = 4,
00139 MAVLINK_TYPE_UINT32_T = 5,
00140 MAVLINK_TYPE_INT32_T = 6,
00141 MAVLINK_TYPE_UINT64_T = 7,
00142 MAVLINK_TYPE_INT64_T = 8,
00143 MAVLINK_TYPE_FLOAT = 9,
00144 MAVLINK_TYPE_DOUBLE = 10
00145 } mavlink_message_type_t;
00146
00147 #define MAVLINK_MAX_FIELDS 64
00148
00149 typedef struct __mavlink_field_info {
00150 const char *name;
00151 const char *print_format;
00152 mavlink_message_type_t type;
00153 unsigned int array_length;
00154 unsigned int wire_offset;
00155 unsigned int structure_offset;
00156 } mavlink_field_info_t;
00157
00158
00159
00160 typedef struct __mavlink_message_info {
00161 const char *name;
00162 unsigned num_fields;
00163 mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];
00164 } mavlink_message_info_t;
00165
00166 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
00167 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
00168
00169
00170 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00171 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00172
00173 typedef enum {
00174 MAVLINK_COMM_0,
00175 MAVLINK_COMM_1,
00176 MAVLINK_COMM_2,
00177 MAVLINK_COMM_3
00178 } mavlink_channel_t;
00179
00180
00181
00182
00183
00184
00185 #ifndef MAVLINK_COMM_NUM_BUFFERS
00186 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
00187 # define MAVLINK_COMM_NUM_BUFFERS 16
00188 #else
00189 # define MAVLINK_COMM_NUM_BUFFERS 4
00190 #endif
00191 #endif
00192
00193 typedef enum {
00194 MAVLINK_PARSE_STATE_UNINIT=0,
00195 MAVLINK_PARSE_STATE_IDLE,
00196 MAVLINK_PARSE_STATE_GOT_STX,
00197 MAVLINK_PARSE_STATE_GOT_SEQ,
00198 MAVLINK_PARSE_STATE_GOT_LENGTH,
00199 MAVLINK_PARSE_STATE_GOT_SYSID,
00200 MAVLINK_PARSE_STATE_GOT_COMPID,
00201 MAVLINK_PARSE_STATE_GOT_MSGID,
00202 MAVLINK_PARSE_STATE_GOT_PAYLOAD,
00203 MAVLINK_PARSE_STATE_GOT_CRC1,
00204 MAVLINK_PARSE_STATE_GOT_BAD_CRC1
00205 } mavlink_parse_state_t;
00206
00207 typedef enum {
00208 MAVLINK_FRAMING_INCOMPLETE=0,
00209 MAVLINK_FRAMING_OK=1,
00210 MAVLINK_FRAMING_BAD_CRC=2
00211 } mavlink_framing_t;
00212
00213 typedef struct __mavlink_status {
00214 uint8_t msg_received;
00215 uint8_t buffer_overrun;
00216 uint8_t parse_error;
00217 mavlink_parse_state_t parse_state;
00218 uint8_t packet_idx;
00219 uint8_t current_rx_seq;
00220 uint8_t current_tx_seq;
00221 uint16_t packet_rx_success_count;
00222 uint16_t packet_rx_drop_count;
00223 } mavlink_status_t;
00224
00225 #define MAVLINK_BIG_ENDIAN 0
00226 #define MAVLINK_LITTLE_ENDIAN 1
00227
00228 #endif