00001 #ifndef MAVLINK_TYPES_H_
00002 #define MAVLINK_TYPES_H_
00003
00004 #include "inttypes.h"
00005
00006 enum MAV_CLASS
00007 {
00008 MAV_CLASS_GENERIC = 0,
00009 MAV_CLASS_PIXHAWK = 1,
00010 MAV_CLASS_SLUGS = 2,
00011 MAV_CLASS_ARDUPILOTMEGA = 3,
00012 MAV_CLASS_OPENPILOT = 4,
00013 MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5,
00014 MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6,
00015 MAV_CLASS_GENERIC_MISSION_FULL = 7,
00016 MAV_CLASS_NONE = 8,
00017 MAV_CLASS_NB
00018 };
00019
00020 enum MAV_ACTION
00021 {
00022 MAV_ACTION_HOLD = 0,
00023 MAV_ACTION_MOTORS_START = 1,
00024 MAV_ACTION_LAUNCH = 2,
00025 MAV_ACTION_RETURN = 3,
00026 MAV_ACTION_EMCY_LAND = 4,
00027 MAV_ACTION_EMCY_KILL = 5,
00028 MAV_ACTION_CONFIRM_KILL = 6,
00029 MAV_ACTION_CONTINUE = 7,
00030 MAV_ACTION_MOTORS_STOP = 8,
00031 MAV_ACTION_HALT = 9,
00032 MAV_ACTION_SHUTDOWN = 10,
00033 MAV_ACTION_REBOOT = 11,
00034 MAV_ACTION_SET_MANUAL = 12,
00035 MAV_ACTION_SET_AUTO = 13,
00036 MAV_ACTION_STORAGE_READ = 14,
00037 MAV_ACTION_STORAGE_WRITE = 15,
00038 MAV_ACTION_CALIBRATE_RC = 16,
00039 MAV_ACTION_CALIBRATE_GYRO = 17,
00040 MAV_ACTION_CALIBRATE_MAG = 18,
00041 MAV_ACTION_CALIBRATE_ACC = 19,
00042 MAV_ACTION_CALIBRATE_PRESSURE = 20,
00043 MAV_ACTION_REC_START = 21,
00044 MAV_ACTION_REC_PAUSE = 22,
00045 MAV_ACTION_REC_STOP = 23,
00046 MAV_ACTION_TAKEOFF = 24,
00047 MAV_ACTION_NAVIGATE = 25,
00048 MAV_ACTION_LAND = 26,
00049 MAV_ACTION_LOITER = 27,
00050 MAV_ACTION_SET_ORIGIN = 28,
00051 MAV_ACTION_RELAY_ON = 29,
00052 MAV_ACTION_RELAY_OFF = 30,
00053 MAV_ACTION_GET_IMAGE = 31,
00054 MAV_ACTION_VIDEO_START = 32,
00055 MAV_ACTION_VIDEO_STOP = 33,
00056 MAV_ACTION_RESET_MAP = 34,
00057 MAV_ACTION_RESET_PLAN = 35,
00058 MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
00059 MAV_ACTION_ASCEND_AT_RATE = 37,
00060 MAV_ACTION_CHANGE_MODE = 38,
00061 MAV_ACTION_LOITER_MAX_TURNS = 39,
00062 MAV_ACTION_LOITER_MAX_TIME = 40,
00063 MAV_ACTION_START_HILSIM = 41,
00064 MAV_ACTION_STOP_HILSIM = 42,
00065 MAV_ACTION_NB
00066 };
00067
00068 enum MAV_MODE
00069 {
00070 MAV_MODE_UNINIT = 0,
00071 MAV_MODE_LOCKED = 1,
00072 MAV_MODE_MANUAL = 2,
00073 MAV_MODE_GUIDED = 3,
00074 MAV_MODE_AUTO = 4,
00075 MAV_MODE_TEST1 = 5,
00076 MAV_MODE_TEST2 = 6,
00077 MAV_MODE_TEST3 = 7,
00078 MAV_MODE_READY = 8,
00079 MAV_MODE_RC_TRAINING = 9
00080 };
00081
00082 enum MAV_STATE
00083 {
00084 MAV_STATE_UNINIT = 0,
00085 MAV_STATE_BOOT,
00086 MAV_STATE_CALIBRATING,
00087 MAV_STATE_STANDBY,
00088 MAV_STATE_ACTIVE,
00089 MAV_STATE_CRITICAL,
00090 MAV_STATE_EMERGENCY,
00091 MAV_STATE_HILSIM,
00092 MAV_STATE_POWEROFF
00093 };
00094
00095 enum MAV_NAV
00096 {
00097 MAV_NAV_GROUNDED = 0,
00098 MAV_NAV_LIFTOFF,
00099 MAV_NAV_HOLD,
00100 MAV_NAV_WAYPOINT,
00101 MAV_NAV_VECTOR,
00102 MAV_NAV_RETURNING,
00103 MAV_NAV_LANDING,
00104 MAV_NAV_LOST,
00105 MAV_NAV_LOITER,
00106 MAV_NAV_FREE_DRIFT
00107 };
00108
00109 enum MAV_TYPE
00110 {
00111 MAV_GENERIC = 0,
00112 MAV_FIXED_WING = 1,
00113 MAV_QUADROTOR = 2,
00114 MAV_COAXIAL = 3,
00115 MAV_HELICOPTER = 4,
00116 MAV_GROUND = 5,
00117 OCU = 6,
00118 MAV_AIRSHIP = 7,
00119 MAV_FREE_BALLOON = 8,
00120 MAV_ROCKET = 9,
00121 UGV_GROUND_ROVER = 10,
00122 UGV_SURFACE_SHIP = 11
00123 };
00124
00125 enum MAV_AUTOPILOT_TYPE
00126 {
00127 MAV_AUTOPILOT_GENERIC = 0,
00128 MAV_AUTOPILOT_PIXHAWK = 1,
00129 MAV_AUTOPILOT_SLUGS = 2,
00130 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
00131 MAV_AUTOPILOT_NONE = 4
00132 };
00133
00134 enum MAV_COMPONENT
00135 {
00136 MAV_COMP_ID_GPS,
00137 MAV_COMP_ID_WAYPOINTPLANNER,
00138 MAV_COMP_ID_BLOBTRACKER,
00139 MAV_COMP_ID_PATHPLANNER,
00140 MAV_COMP_ID_AIRSLAM,
00141 MAV_COMP_ID_MAPPER,
00142 MAV_COMP_ID_CAMERA,
00143 MAV_COMP_ID_RADIO = 68,
00144 MAV_COMP_ID_IMU = 200,
00145 MAV_COMP_ID_IMU_2 = 201,
00146 MAV_COMP_ID_IMU_3 = 202,
00147 MAV_COMP_ID_UDP_BRIDGE = 240,
00148 MAV_COMP_ID_UART_BRIDGE = 241,
00149 MAV_COMP_ID_SYSTEM_CONTROL = 250
00150 };
00151
00152 enum MAV_FRAME
00153 {
00154 MAV_FRAME_GLOBAL = 0,
00155 MAV_FRAME_LOCAL = 1,
00156 MAV_FRAME_MISSION = 2,
00157 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
00158 MAV_FRAME_LOCAL_ENU = 4
00159 };
00160
00161 enum MAVLINK_DATA_STREAM_TYPE
00162 {
00163 MAVLINK_DATA_STREAM_IMG_JPEG,
00164 MAVLINK_DATA_STREAM_IMG_BMP,
00165 MAVLINK_DATA_STREAM_IMG_RAW8U,
00166 MAVLINK_DATA_STREAM_IMG_RAW32U,
00167 MAVLINK_DATA_STREAM_IMG_PGM,
00168 MAVLINK_DATA_STREAM_IMG_PNG
00169 };
00170
00171 #ifndef MAVLINK_MAX_PAYLOAD_LEN
00172
00173 #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
00174 #endif
00175
00176 #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)
00177 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
00178 #define MAVLINK_NUM_CHECKSUM_BYTES 2
00179 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
00180
00181 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
00182
00183 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
00184 #define MAVLINK_EXTENDED_HEADER_LEN 14
00185
00186 #if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
00187
00188 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
00189 #else
00190
00191 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
00192 #endif
00193
00194 #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
00195
00196 typedef struct param_union {
00197 union {
00198 float param_float;
00199 int32_t param_int32;
00200 uint32_t param_uint32;
00201 uint8_t param_uint8;
00202 uint8_t bytes[4];
00203 };
00204 uint8_t type;
00205 } mavlink_param_union_t;
00206
00207 typedef struct __mavlink_system {
00208 uint8_t sysid;
00209 uint8_t compid;
00210 uint8_t type;
00211 uint8_t state;
00212 uint8_t mode;
00213 uint8_t nav_mode;
00214 } mavlink_system_t;
00215
00216 typedef struct __mavlink_message {
00217 uint16_t checksum;
00218 uint8_t magic;
00219 uint8_t len;
00220 uint8_t seq;
00221 uint8_t sysid;
00222 uint8_t compid;
00223 uint8_t msgid;
00224 uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
00225 } mavlink_message_t;
00226
00227
00228 typedef struct __mavlink_extended_message {
00229 mavlink_message_t base_msg;
00230 int32_t extended_payload_len;
00231 uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
00232 } mavlink_extended_message_t;
00233
00234
00235 typedef enum {
00236 MAVLINK_TYPE_CHAR = 0,
00237 MAVLINK_TYPE_UINT8_T = 1,
00238 MAVLINK_TYPE_INT8_T = 2,
00239 MAVLINK_TYPE_UINT16_T = 3,
00240 MAVLINK_TYPE_INT16_T = 4,
00241 MAVLINK_TYPE_UINT32_T = 5,
00242 MAVLINK_TYPE_INT32_T = 6,
00243 MAVLINK_TYPE_UINT64_T = 7,
00244 MAVLINK_TYPE_INT64_T = 8,
00245 MAVLINK_TYPE_FLOAT = 9,
00246 MAVLINK_TYPE_DOUBLE = 10
00247 } mavlink_message_type_t;
00248
00249 #define MAVLINK_MAX_FIELDS 64
00250
00251 typedef struct __mavlink_field_info {
00252 const char *name;
00253 const char *print_format;
00254 mavlink_message_type_t type;
00255 unsigned int array_length;
00256 unsigned int wire_offset;
00257 unsigned int structure_offset;
00258 } mavlink_field_info_t;
00259
00260
00261
00262 typedef struct __mavlink_message_info {
00263 const char *name;
00264 unsigned num_fields;
00265 mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];
00266 } mavlink_message_info_t;
00267
00268 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
00269 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
00270
00271
00272 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00273 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00274
00275 typedef enum {
00276 MAVLINK_COMM_0,
00277 MAVLINK_COMM_1,
00278 MAVLINK_COMM_2,
00279 MAVLINK_COMM_3
00280 } mavlink_channel_t;
00281
00282
00283
00284
00285
00286
00287 #ifndef MAVLINK_COMM_NUM_BUFFERS
00288 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
00289 # define MAVLINK_COMM_NUM_BUFFERS 16
00290 #else
00291 # define MAVLINK_COMM_NUM_BUFFERS 4
00292 #endif
00293 #endif
00294
00295 typedef enum {
00296 MAVLINK_PARSE_STATE_UNINIT=0,
00297 MAVLINK_PARSE_STATE_IDLE,
00298 MAVLINK_PARSE_STATE_GOT_STX,
00299 MAVLINK_PARSE_STATE_GOT_SEQ,
00300 MAVLINK_PARSE_STATE_GOT_LENGTH,
00301 MAVLINK_PARSE_STATE_GOT_SYSID,
00302 MAVLINK_PARSE_STATE_GOT_COMPID,
00303 MAVLINK_PARSE_STATE_GOT_MSGID,
00304 MAVLINK_PARSE_STATE_GOT_PAYLOAD,
00305 MAVLINK_PARSE_STATE_GOT_CRC1
00306 } mavlink_parse_state_t;
00307
00308 typedef struct __mavlink_status {
00309 uint8_t msg_received;
00310 uint8_t buffer_overrun;
00311 uint8_t parse_error;
00312 mavlink_parse_state_t parse_state;
00313 uint8_t packet_idx;
00314 uint8_t current_rx_seq;
00315 uint8_t current_tx_seq;
00316 uint16_t packet_rx_success_count;
00317 uint16_t packet_rx_drop_count;
00318 } mavlink_status_t;
00319
00320 #define MAVLINK_BIG_ENDIAN 0
00321 #define MAVLINK_LITTLE_ENDIAN 1
00322
00323 #endif