common.h
Go to the documentation of this file.
00001 
00005 #ifndef MAVLINK_COMMON_H
00006 #define MAVLINK_COMMON_H
00007 
00008 #ifndef MAVLINK_H
00009     #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
00010 #endif
00011 
00012 #ifdef __cplusplus
00013 extern "C" {
00014 #endif
00015 
00016 // MESSAGE LENGTHS AND CRCS
00017 
00018 #ifndef MAVLINK_MESSAGE_LENGTHS
00019 #define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 24, 243, 14, 0, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
00020 #endif
00021 
00022 #ifndef MAVLINK_MESSAGE_CRCS
00023 #define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 148, 72, 131, 0, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
00024 #endif
00025 
00026 #ifndef MAVLINK_MESSAGE_INFO
00027 #define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
00028 #endif
00029 
00030 #include "../protocol.h"
00031 
00032 #define MAVLINK_ENABLED_COMMON
00033 
00034 // ENUM DEFINITIONS
00035 
00036 
00038 #ifndef HAVE_ENUM_MAV_AUTOPILOT
00039 #define HAVE_ENUM_MAV_AUTOPILOT
00040 typedef enum MAV_AUTOPILOT
00041 {
00042         MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
00043         MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */
00044         MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
00045         MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */
00046         MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
00047         MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
00048         MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
00049         MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
00050         MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
00051         MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
00052         MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
00053         MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
00054         MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */
00055         MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */
00056         MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */
00057         MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */
00058         MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */
00059         MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */
00060         MAV_AUTOPILOT_ENUM_END=18, /*  | */
00061 } MAV_AUTOPILOT;
00062 #endif
00063 
00065 #ifndef HAVE_ENUM_MAV_TYPE
00066 #define HAVE_ENUM_MAV_TYPE
00067 typedef enum MAV_TYPE
00068 {
00069         MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
00070         MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
00071         MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
00072         MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
00073         MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
00074         MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
00075         MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
00076         MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
00077         MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
00078         MAV_TYPE_ROCKET=9, /* Rocket | */
00079         MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
00080         MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
00081         MAV_TYPE_SUBMARINE=12, /* Submarine | */
00082         MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
00083         MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
00084         MAV_TYPE_TRICOPTER=15, /* Octorotor | */
00085         MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
00086         MAV_TYPE_KITE=17, /* Flapping wing | */
00087         MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
00088         MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */
00089         MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */
00090         MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */
00091         MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */
00092         MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */
00093         MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */
00094         MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */
00095         MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */
00096         MAV_TYPE_ENUM_END=27, /*  | */
00097 } MAV_TYPE;
00098 #endif
00099 
00101 #ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE
00102 #define HAVE_ENUM_FIRMWARE_VERSION_TYPE
00103 typedef enum FIRMWARE_VERSION_TYPE
00104 {
00105         FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */
00106         FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */
00107         FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */
00108         FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */
00109         FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */
00110         FIRMWARE_VERSION_TYPE_ENUM_END=256, /*  | */
00111 } FIRMWARE_VERSION_TYPE;
00112 #endif
00113 
00115 #ifndef HAVE_ENUM_MAV_MODE_FLAG
00116 #define HAVE_ENUM_MAV_MODE_FLAG
00117 typedef enum MAV_MODE_FLAG
00118 {
00119         MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
00120         MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
00121         MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
00122         MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
00123         MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
00124         MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
00125         MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
00126         MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
00127         MAV_MODE_FLAG_ENUM_END=129, /*  | */
00128 } MAV_MODE_FLAG;
00129 #endif
00130 
00132 #ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
00133 #define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
00134 typedef enum MAV_MODE_FLAG_DECODE_POSITION
00135 {
00136         MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
00137         MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
00138         MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit:   00000100 | */
00139         MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit:  00001000 | */
00140         MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
00141         MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit:  00100000 | */
00142         MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
00143         MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit:  10000000 | */
00144         MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /*  | */
00145 } MAV_MODE_FLAG_DECODE_POSITION;
00146 #endif
00147 
00149 #ifndef HAVE_ENUM_MAV_GOTO
00150 #define HAVE_ENUM_MAV_GOTO
00151 typedef enum MAV_GOTO
00152 {
00153         MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */
00154         MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */
00155         MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */
00156         MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */
00157         MAV_GOTO_ENUM_END=4, /*  | */
00158 } MAV_GOTO;
00159 #endif
00160 
00163 #ifndef HAVE_ENUM_MAV_MODE
00164 #define HAVE_ENUM_MAV_MODE
00165 typedef enum MAV_MODE
00166 {
00167         MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
00168         MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */
00169         MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
00170         MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */
00171         MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */
00172         MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
00173         MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */
00174         MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
00175         MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */
00176         MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */
00177         MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
00178         MAV_MODE_ENUM_END=221, /*  | */
00179 } MAV_MODE;
00180 #endif
00181 
00183 #ifndef HAVE_ENUM_MAV_STATE
00184 #define HAVE_ENUM_MAV_STATE
00185 typedef enum MAV_STATE
00186 {
00187         MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
00188         MAV_STATE_BOOT=1, /* System is booting up. | */
00189         MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
00190         MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
00191         MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
00192         MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
00193         MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */
00194         MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
00195         MAV_STATE_ENUM_END=8, /*  | */
00196 } MAV_STATE;
00197 #endif
00198 
00200 #ifndef HAVE_ENUM_MAV_COMPONENT
00201 #define HAVE_ENUM_MAV_COMPONENT
00202 typedef enum MAV_COMPONENT
00203 {
00204         MAV_COMP_ID_ALL=0, /*  | */
00205         MAV_COMP_ID_CAMERA=100, /*  | */
00206         MAV_COMP_ID_SERVO1=140, /*  | */
00207         MAV_COMP_ID_SERVO2=141, /*  | */
00208         MAV_COMP_ID_SERVO3=142, /*  | */
00209         MAV_COMP_ID_SERVO4=143, /*  | */
00210         MAV_COMP_ID_SERVO5=144, /*  | */
00211         MAV_COMP_ID_SERVO6=145, /*  | */
00212         MAV_COMP_ID_SERVO7=146, /*  | */
00213         MAV_COMP_ID_SERVO8=147, /*  | */
00214         MAV_COMP_ID_SERVO9=148, /*  | */
00215         MAV_COMP_ID_SERVO10=149, /*  | */
00216         MAV_COMP_ID_SERVO11=150, /*  | */
00217         MAV_COMP_ID_SERVO12=151, /*  | */
00218         MAV_COMP_ID_SERVO13=152, /*  | */
00219         MAV_COMP_ID_SERVO14=153, /*  | */
00220         MAV_COMP_ID_GIMBAL=154, /*  | */
00221         MAV_COMP_ID_MAPPER=180, /*  | */
00222         MAV_COMP_ID_MISSIONPLANNER=190, /*  | */
00223         MAV_COMP_ID_PATHPLANNER=195, /*  | */
00224         MAV_COMP_ID_IMU=200, /*  | */
00225         MAV_COMP_ID_IMU_2=201, /*  | */
00226         MAV_COMP_ID_IMU_3=202, /*  | */
00227         MAV_COMP_ID_GPS=220, /*  | */
00228         MAV_COMP_ID_UDP_BRIDGE=240, /*  | */
00229         MAV_COMP_ID_UART_BRIDGE=241, /*  | */
00230         MAV_COMP_ID_SYSTEM_CONTROL=250, /*  | */
00231         MAV_COMPONENT_ENUM_END=251, /*  | */
00232 } MAV_COMPONENT;
00233 #endif
00234 
00236 #ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR
00237 #define HAVE_ENUM_MAV_SYS_STATUS_SENSOR
00238 typedef enum MAV_SYS_STATUS_SENSOR
00239 {
00240         MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */
00241         MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */
00242         MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */
00243         MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */
00244         MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */
00245         MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */
00246         MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */
00247         MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */
00248         MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */
00249         MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */
00250         MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */
00251         MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */
00252         MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */
00253         MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */
00254         MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */
00255         MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */
00256         MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */
00257         MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */
00258         MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */
00259         MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */
00260         MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */
00261         MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */
00262         MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */
00263         MAV_SYS_STATUS_SENSOR_ENUM_END=4194305, /*  | */
00264 } MAV_SYS_STATUS_SENSOR;
00265 #endif
00266 
00268 #ifndef HAVE_ENUM_MAV_FRAME
00269 #define HAVE_ENUM_MAV_FRAME
00270 typedef enum MAV_FRAME
00271 {
00272         MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */
00273         MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */
00274         MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
00275         MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */
00276         MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
00277         MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */
00278         MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */
00279         MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */
00280         MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */
00281         MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */
00282         MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */
00283         MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */
00284         MAV_FRAME_ENUM_END=12, /*  | */
00285 } MAV_FRAME;
00286 #endif
00287 
00289 #ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
00290 #define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
00291 typedef enum MAVLINK_DATA_STREAM_TYPE
00292 {
00293         MAVLINK_DATA_STREAM_IMG_JPEG=1, /*  | */
00294         MAVLINK_DATA_STREAM_IMG_BMP=2, /*  | */
00295         MAVLINK_DATA_STREAM_IMG_RAW8U=3, /*  | */
00296         MAVLINK_DATA_STREAM_IMG_RAW32U=4, /*  | */
00297         MAVLINK_DATA_STREAM_IMG_PGM=5, /*  | */
00298         MAVLINK_DATA_STREAM_IMG_PNG=6, /*  | */
00299         MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /*  | */
00300 } MAVLINK_DATA_STREAM_TYPE;
00301 #endif
00302 
00304 #ifndef HAVE_ENUM_FENCE_ACTION
00305 #define HAVE_ENUM_FENCE_ACTION
00306 typedef enum FENCE_ACTION
00307 {
00308         FENCE_ACTION_NONE=0, /* Disable fenced mode | */
00309         FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
00310         FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */
00311         FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */
00312         FENCE_ACTION_ENUM_END=4, /*  | */
00313 } FENCE_ACTION;
00314 #endif
00315 
00317 #ifndef HAVE_ENUM_FENCE_BREACH
00318 #define HAVE_ENUM_FENCE_BREACH
00319 typedef enum FENCE_BREACH
00320 {
00321         FENCE_BREACH_NONE=0, /* No last fence breach | */
00322         FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
00323         FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */
00324         FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
00325         FENCE_BREACH_ENUM_END=4, /*  | */
00326 } FENCE_BREACH;
00327 #endif
00328 
00330 #ifndef HAVE_ENUM_MAV_MOUNT_MODE
00331 #define HAVE_ENUM_MAV_MOUNT_MODE
00332 typedef enum MAV_MOUNT_MODE
00333 {
00334         MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */
00335         MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */
00336         MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
00337         MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
00338         MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
00339         MAV_MOUNT_MODE_ENUM_END=5, /*  | */
00340 } MAV_MOUNT_MODE;
00341 #endif
00342 
00344 #ifndef HAVE_ENUM_MAV_CMD
00345 #define HAVE_ENUM_MAV_CMD
00346 typedef enum MAV_CMD
00347 {
00348         MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude|  */
00349         MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
00350         MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
00351         MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
00352         MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
00353         MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude|  */
00354         MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|  */
00355         MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]|  */
00356         MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]|  */
00357         MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
00358         MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude.  When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters|  */
00359         MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude.  If Lat=Lon=0, then loiter at the current position.  Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached.  Additionally, if the Heading Required parameter is non-zero the  aircraft will not leave the loiter until heading toward the next waypoint.  |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude|  */
00360         MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|  */
00361         MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|  */
00362         MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|  */
00363         MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00364         MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
00365         MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00366         MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate.  Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|  */
00367         MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00368         MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|  */
00369         MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
00370         MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty|  */
00371         MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list.  Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty|  */
00372         MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed  (m/s, -1 indicates no change)| Throttle  ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty|  */
00373         MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude|  */
00374         MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter.  Caution!  Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty|  */
00375         MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|  */
00376         MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty|  */
00377         MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty|  */
00378         MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty|  */
00379         MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty|  */
00380         MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty|  */
00381         MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty|  */
00382         MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00383         MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|  */
00384         MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|  */
00385         MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|  */
00386         MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|  */
00387         MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|  */
00388         MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value|  */
00389         MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00390         MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00391         MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00392         MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty|  */
00393         MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty|  */
00394         MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|  */
00395         MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue.  0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue.  0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|  */
00396         MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
00397         MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty|  */
00398         MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units|  */
00399         MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved|  */
00400         MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty|  */
00401         MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|  */
00402         MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position|  */
00403         MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item:  the last mission item to run (after this item is run, the mission ends)|  */
00404         MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm|  */
00405         MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved|  */
00406         MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX|  */
00407         MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID|  */
00408         MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.|  */
00409         MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)|  */
00410         MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)|  */
00411         MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved|  */
00412         MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved|  */
00413         MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)|  */
00414         MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved|  */
00415         MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)|  */
00416         MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.|  */
00417         MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL|  */
00418         MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved|  */
00419         MAV_CMD_ENUM_END=30003, /*  | */
00420 } MAV_CMD;
00421 #endif
00422 
00426 #ifndef HAVE_ENUM_MAV_DATA_STREAM
00427 #define HAVE_ENUM_MAV_DATA_STREAM
00428 typedef enum MAV_DATA_STREAM
00429 {
00430         MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
00431         MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
00432         MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
00433         MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
00434         MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
00435         MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
00436         MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
00437         MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
00438         MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
00439         MAV_DATA_STREAM_ENUM_END=13, /*  | */
00440 } MAV_DATA_STREAM;
00441 #endif
00442 
00446 #ifndef HAVE_ENUM_MAV_ROI
00447 #define HAVE_ENUM_MAV_ROI
00448 typedef enum MAV_ROI
00449 {
00450         MAV_ROI_NONE=0, /* No region of interest. | */
00451         MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */
00452         MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */
00453         MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
00454         MAV_ROI_TARGET=4, /* Point toward of given id. | */
00455         MAV_ROI_ENUM_END=5, /*  | */
00456 } MAV_ROI;
00457 #endif
00458 
00460 #ifndef HAVE_ENUM_MAV_CMD_ACK
00461 #define HAVE_ENUM_MAV_CMD_ACK
00462 typedef enum MAV_CMD_ACK
00463 {
00464         MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */
00465         MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */
00466         MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */
00467         MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */
00468         MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */
00469         MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */
00470         MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */
00471         MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */
00472         MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */
00473         MAV_CMD_ACK_ENUM_END=10, /*  | */
00474 } MAV_CMD_ACK;
00475 #endif
00476 
00478 #ifndef HAVE_ENUM_MAV_PARAM_TYPE
00479 #define HAVE_ENUM_MAV_PARAM_TYPE
00480 typedef enum MAV_PARAM_TYPE
00481 {
00482         MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */
00483         MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */
00484         MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */
00485         MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */
00486         MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */
00487         MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */
00488         MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */
00489         MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */
00490         MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */
00491         MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */
00492         MAV_PARAM_TYPE_ENUM_END=11, /*  | */
00493 } MAV_PARAM_TYPE;
00494 #endif
00495 
00497 #ifndef HAVE_ENUM_MAV_RESULT
00498 #define HAVE_ENUM_MAV_RESULT
00499 typedef enum MAV_RESULT
00500 {
00501         MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
00502         MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
00503         MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
00504         MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
00505         MAV_RESULT_FAILED=4, /* Command executed, but failed | */
00506         MAV_RESULT_ENUM_END=5, /*  | */
00507 } MAV_RESULT;
00508 #endif
00509 
00511 #ifndef HAVE_ENUM_MAV_MISSION_RESULT
00512 #define HAVE_ENUM_MAV_MISSION_RESULT
00513 typedef enum MAV_MISSION_RESULT
00514 {
00515         MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */
00516         MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */
00517         MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */
00518         MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */
00519         MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */
00520         MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */
00521         MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */
00522         MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */
00523         MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */
00524         MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */
00525         MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */
00526         MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */
00527         MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */
00528         MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */
00529         MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */
00530         MAV_MISSION_RESULT_ENUM_END=15, /*  | */
00531 } MAV_MISSION_RESULT;
00532 #endif
00533 
00535 #ifndef HAVE_ENUM_MAV_SEVERITY
00536 #define HAVE_ENUM_MAV_SEVERITY
00537 typedef enum MAV_SEVERITY
00538 {
00539         MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */
00540         MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */
00541         MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */
00542         MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */
00543         MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */
00544         MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */
00545         MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */
00546         MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */
00547         MAV_SEVERITY_ENUM_END=8, /*  | */
00548 } MAV_SEVERITY;
00549 #endif
00550 
00552 #ifndef HAVE_ENUM_MAV_POWER_STATUS
00553 #define HAVE_ENUM_MAV_POWER_STATUS
00554 typedef enum MAV_POWER_STATUS
00555 {
00556         MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */
00557         MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */
00558         MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */
00559         MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */
00560         MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */
00561         MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */
00562         MAV_POWER_STATUS_ENUM_END=33, /*  | */
00563 } MAV_POWER_STATUS;
00564 #endif
00565 
00567 #ifndef HAVE_ENUM_SERIAL_CONTROL_DEV
00568 #define HAVE_ENUM_SERIAL_CONTROL_DEV
00569 typedef enum SERIAL_CONTROL_DEV
00570 {
00571         SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */
00572         SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */
00573         SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */
00574         SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */
00575         SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */
00576         SERIAL_CONTROL_DEV_ENUM_END=11, /*  | */
00577 } SERIAL_CONTROL_DEV;
00578 #endif
00579 
00581 #ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG
00582 #define HAVE_ENUM_SERIAL_CONTROL_FLAG
00583 typedef enum SERIAL_CONTROL_FLAG
00584 {
00585         SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */
00586         SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */
00587         SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */
00588         SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */
00589         SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */
00590         SERIAL_CONTROL_FLAG_ENUM_END=17, /*  | */
00591 } SERIAL_CONTROL_FLAG;
00592 #endif
00593 
00595 #ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR
00596 #define HAVE_ENUM_MAV_DISTANCE_SENSOR
00597 typedef enum MAV_DISTANCE_SENSOR
00598 {
00599         MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */
00600         MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */
00601         MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */
00602         MAV_DISTANCE_SENSOR_ENUM_END=3, /*  | */
00603 } MAV_DISTANCE_SENSOR;
00604 #endif
00605 
00607 #ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION
00608 #define HAVE_ENUM_MAV_SENSOR_ORIENTATION
00609 typedef enum MAV_SENSOR_ORIENTATION
00610 {
00611         MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */
00612         MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */
00613         MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */
00614         MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */
00615         MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */
00616         MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */
00617         MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */
00618         MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */
00619         MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */
00620         MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */
00621         MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */
00622         MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */
00623         MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */
00624         MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */
00625         MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */
00626         MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */
00627         MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */
00628         MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */
00629         MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */
00630         MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */
00631         MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */
00632         MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */
00633         MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */
00634         MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */
00635         MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */
00636         MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */
00637         MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */
00638         MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */
00639         MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */
00640         MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */
00641         MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */
00642         MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */
00643         MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */
00644         MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */
00645         MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */
00646         MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */
00647         MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */
00648         MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */
00649         MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */
00650         MAV_SENSOR_ORIENTATION_ENUM_END=39, /*  | */
00651 } MAV_SENSOR_ORIENTATION;
00652 #endif
00653 
00655 #ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY
00656 #define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY
00657 typedef enum MAV_PROTOCOL_CAPABILITY
00658 {
00659         MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */
00660         MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */
00661         MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */
00662         MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */
00663         MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */
00664         MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new param union message type. | */
00665         MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */
00666         MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */
00667         MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */
00668         MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */
00669         MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */
00670         MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */
00671         MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */
00672         MAV_PROTOCOL_CAPABILITY_ENUM_END=4097, /*  | */
00673 } MAV_PROTOCOL_CAPABILITY;
00674 #endif
00675 
00677 #ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE
00678 #define HAVE_ENUM_MAV_ESTIMATOR_TYPE
00679 typedef enum MAV_ESTIMATOR_TYPE
00680 {
00681         MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */
00682         MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */
00683         MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */
00684         MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */
00685         MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */
00686         MAV_ESTIMATOR_TYPE_ENUM_END=6, /*  | */
00687 } MAV_ESTIMATOR_TYPE;
00688 #endif
00689 
00691 #ifndef HAVE_ENUM_MAV_BATTERY_TYPE
00692 #define HAVE_ENUM_MAV_BATTERY_TYPE
00693 typedef enum MAV_BATTERY_TYPE
00694 {
00695         MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */
00696         MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymere battery | */
00697         MAV_BATTERY_TYPE_LIFE=2, /* Lithium ferrite battery | */
00698         MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */
00699         MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */
00700         MAV_BATTERY_TYPE_ENUM_END=5, /*  | */
00701 } MAV_BATTERY_TYPE;
00702 #endif
00703 
00705 #ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION
00706 #define HAVE_ENUM_MAV_BATTERY_FUNCTION
00707 typedef enum MAV_BATTERY_FUNCTION
00708 {
00709         MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Lithium polymere battery | */
00710         MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */
00711         MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */
00712         MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */
00713         MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */
00714         MAV_BATTERY_FUNCTION_ENUM_END=5, /*  | */
00715 } MAV_BATTERY_FUNCTION;
00716 #endif
00717 
00719 #ifndef HAVE_ENUM_MAV_VTOL_STATE
00720 #define HAVE_ENUM_MAV_VTOL_STATE
00721 typedef enum MAV_VTOL_STATE
00722 {
00723         MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */
00724         MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */
00725         MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */
00726         MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */
00727         MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */
00728         MAV_VTOL_STATE_ENUM_END=5, /*  | */
00729 } MAV_VTOL_STATE;
00730 #endif
00731 
00733 #ifndef HAVE_ENUM_MAV_LANDED_STATE
00734 #define HAVE_ENUM_MAV_LANDED_STATE
00735 typedef enum MAV_LANDED_STATE
00736 {
00737         MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */
00738         MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */
00739         MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */
00740         MAV_LANDED_STATE_ENUM_END=3, /*  | */
00741 } MAV_LANDED_STATE;
00742 #endif
00743 
00744 
00745 
00746 // MAVLINK VERSION
00747 
00748 #ifndef MAVLINK_VERSION
00749 #define MAVLINK_VERSION 3
00750 #endif
00751 
00752 #if (MAVLINK_VERSION == 0)
00753 #undef MAVLINK_VERSION
00754 #define MAVLINK_VERSION 3
00755 #endif
00756 
00757 // MESSAGE DEFINITIONS
00758 #include "./mavlink_msg_heartbeat.h"
00759 #include "./mavlink_msg_sys_status.h"
00760 #include "./mavlink_msg_system_time.h"
00761 #include "./mavlink_msg_ping.h"
00762 #include "./mavlink_msg_change_operator_control.h"
00763 #include "./mavlink_msg_change_operator_control_ack.h"
00764 #include "./mavlink_msg_auth_key.h"
00765 #include "./mavlink_msg_set_mode.h"
00766 #include "./mavlink_msg_param_request_read.h"
00767 #include "./mavlink_msg_param_request_list.h"
00768 #include "./mavlink_msg_param_value.h"
00769 #include "./mavlink_msg_param_set.h"
00770 #include "./mavlink_msg_gps_raw_int.h"
00771 #include "./mavlink_msg_gps_status.h"
00772 #include "./mavlink_msg_scaled_imu.h"
00773 #include "./mavlink_msg_raw_imu.h"
00774 #include "./mavlink_msg_raw_pressure.h"
00775 #include "./mavlink_msg_scaled_pressure.h"
00776 #include "./mavlink_msg_attitude.h"
00777 #include "./mavlink_msg_attitude_quaternion.h"
00778 #include "./mavlink_msg_local_position_ned.h"
00779 #include "./mavlink_msg_global_position_int.h"
00780 #include "./mavlink_msg_rc_channels_scaled.h"
00781 #include "./mavlink_msg_rc_channels_raw.h"
00782 #include "./mavlink_msg_servo_output_raw.h"
00783 #include "./mavlink_msg_mission_request_partial_list.h"
00784 #include "./mavlink_msg_mission_write_partial_list.h"
00785 #include "./mavlink_msg_mission_item.h"
00786 #include "./mavlink_msg_mission_request.h"
00787 #include "./mavlink_msg_mission_set_current.h"
00788 #include "./mavlink_msg_mission_current.h"
00789 #include "./mavlink_msg_mission_request_list.h"
00790 #include "./mavlink_msg_mission_count.h"
00791 #include "./mavlink_msg_mission_clear_all.h"
00792 #include "./mavlink_msg_mission_item_reached.h"
00793 #include "./mavlink_msg_mission_ack.h"
00794 #include "./mavlink_msg_set_gps_global_origin.h"
00795 #include "./mavlink_msg_gps_global_origin.h"
00796 #include "./mavlink_msg_param_map_rc.h"
00797 #include "./mavlink_msg_safety_set_allowed_area.h"
00798 #include "./mavlink_msg_safety_allowed_area.h"
00799 #include "./mavlink_msg_attitude_quaternion_cov.h"
00800 #include "./mavlink_msg_nav_controller_output.h"
00801 #include "./mavlink_msg_global_position_int_cov.h"
00802 #include "./mavlink_msg_local_position_ned_cov.h"
00803 #include "./mavlink_msg_rc_channels.h"
00804 #include "./mavlink_msg_request_data_stream.h"
00805 #include "./mavlink_msg_data_stream.h"
00806 #include "./mavlink_msg_manual_control.h"
00807 #include "./mavlink_msg_rc_channels_override.h"
00808 #include "./mavlink_msg_mission_item_int.h"
00809 #include "./mavlink_msg_vfr_hud.h"
00810 #include "./mavlink_msg_command_int.h"
00811 #include "./mavlink_msg_command_long.h"
00812 #include "./mavlink_msg_command_ack.h"
00813 #include "./mavlink_msg_manual_setpoint.h"
00814 #include "./mavlink_msg_set_attitude_target.h"
00815 #include "./mavlink_msg_attitude_target.h"
00816 #include "./mavlink_msg_set_position_target_local_ned.h"
00817 #include "./mavlink_msg_position_target_local_ned.h"
00818 #include "./mavlink_msg_set_position_target_global_int.h"
00819 #include "./mavlink_msg_position_target_global_int.h"
00820 #include "./mavlink_msg_local_position_ned_system_global_offset.h"
00821 #include "./mavlink_msg_hil_state.h"
00822 #include "./mavlink_msg_hil_controls.h"
00823 #include "./mavlink_msg_hil_rc_inputs_raw.h"
00824 #include "./mavlink_msg_optical_flow.h"
00825 #include "./mavlink_msg_global_vision_position_estimate.h"
00826 #include "./mavlink_msg_vision_position_estimate.h"
00827 #include "./mavlink_msg_vision_speed_estimate.h"
00828 #include "./mavlink_msg_vicon_position_estimate.h"
00829 #include "./mavlink_msg_highres_imu.h"
00830 #include "./mavlink_msg_optical_flow_rad.h"
00831 #include "./mavlink_msg_hil_sensor.h"
00832 #include "./mavlink_msg_sim_state.h"
00833 #include "./mavlink_msg_radio_status.h"
00834 #include "./mavlink_msg_file_transfer_protocol.h"
00835 #include "./mavlink_msg_timesync.h"
00836 #include "./mavlink_msg_camera_trigger.h"
00837 #include "./mavlink_msg_hil_gps.h"
00838 #include "./mavlink_msg_hil_optical_flow.h"
00839 #include "./mavlink_msg_hil_state_quaternion.h"
00840 #include "./mavlink_msg_scaled_imu2.h"
00841 #include "./mavlink_msg_log_request_list.h"
00842 #include "./mavlink_msg_log_entry.h"
00843 #include "./mavlink_msg_log_request_data.h"
00844 #include "./mavlink_msg_log_data.h"
00845 #include "./mavlink_msg_log_erase.h"
00846 #include "./mavlink_msg_log_request_end.h"
00847 #include "./mavlink_msg_gps_inject_data.h"
00848 #include "./mavlink_msg_gps2_raw.h"
00849 #include "./mavlink_msg_power_status.h"
00850 #include "./mavlink_msg_serial_control.h"
00851 #include "./mavlink_msg_gps_rtk.h"
00852 #include "./mavlink_msg_gps2_rtk.h"
00853 #include "./mavlink_msg_scaled_imu3.h"
00854 #include "./mavlink_msg_data_transmission_handshake.h"
00855 #include "./mavlink_msg_encapsulated_data.h"
00856 #include "./mavlink_msg_distance_sensor.h"
00857 #include "./mavlink_msg_terrain_request.h"
00858 #include "./mavlink_msg_terrain_data.h"
00859 #include "./mavlink_msg_terrain_check.h"
00860 #include "./mavlink_msg_terrain_report.h"
00861 #include "./mavlink_msg_scaled_pressure2.h"
00862 #include "./mavlink_msg_att_pos_mocap.h"
00863 #include "./mavlink_msg_set_actuator_control_target.h"
00864 #include "./mavlink_msg_actuator_control_target.h"
00865 #include "./mavlink_msg_altitude.h"
00866 #include "./mavlink_msg_resource_request.h"
00867 #include "./mavlink_msg_scaled_pressure3.h"
00868 #include "./mavlink_msg_control_system_state.h"
00869 #include "./mavlink_msg_battery_status.h"
00870 #include "./mavlink_msg_autopilot_version.h"
00871 #include "./mavlink_msg_landing_target.h"
00872 #include "./mavlink_msg_vibration.h"
00873 #include "./mavlink_msg_home_position.h"
00874 #include "./mavlink_msg_set_home_position.h"
00875 #include "./mavlink_msg_message_interval.h"
00876 #include "./mavlink_msg_extended_sys_state.h"
00877 #include "./mavlink_msg_v2_extension.h"
00878 #include "./mavlink_msg_memory_vect.h"
00879 #include "./mavlink_msg_debug_vect.h"
00880 #include "./mavlink_msg_named_value_float.h"
00881 #include "./mavlink_msg_named_value_int.h"
00882 #include "./mavlink_msg_statustext.h"
00883 #include "./mavlink_msg_debug.h"
00884 
00885 #ifdef __cplusplus
00886 }
00887 #endif // __cplusplus
00888 #endif // MAVLINK_COMMON_H


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:34