aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/autoquad
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-12-16 09:04:03 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-12-16 09:04:03 +0100
commit43582cdb6843cdcfdc8f0deba1439b6c3fe7e417 (patch)
treef6518a61d17034b396102da5939a616ee37e17cb /mavlink/include/mavlink/v1.0/autoquad
parentae26e70f54f6cdc39d15f708c5d727f51ee882f7 (diff)
downloadpx4-firmware-43582cdb6843cdcfdc8f0deba1439b6c3fe7e417.tar.gz
px4-firmware-43582cdb6843cdcfdc8f0deba1439b6c3fe7e417.tar.bz2
px4-firmware-43582cdb6843cdcfdc8f0deba1439b6c3fe7e417.zip
Re-introduced AQ MAVLink files since we have had them around before
Diffstat (limited to 'mavlink/include/mavlink/v1.0/autoquad')
-rw-r--r--mavlink/include/mavlink/v1.0/autoquad/autoquad.h123
-rw-r--r--mavlink/include/mavlink/v1.0/autoquad/mavlink.h27
-rw-r--r--mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h617
-rw-r--r--mavlink/include/mavlink/v1.0/autoquad/testsuite.h118
-rw-r--r--mavlink/include/mavlink/v1.0/autoquad/version.h12
5 files changed, 897 insertions, 0 deletions
diff --git a/mavlink/include/mavlink/v1.0/autoquad/autoquad.h b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h
new file mode 100644
index 000000000..281aa8975
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h
@@ -0,0 +1,123 @@
+/** @file
+ * @brief MAVLink comm protocol generated from autoquad.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef AUTOQUAD_H
+#define AUTOQUAD_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#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, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 82, 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, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#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, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 241, 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, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#endif
+
+#ifndef MAVLINK_MESSAGE_INFO
+#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_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"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_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_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, 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, {"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_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F, {"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}}}, {"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_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}}}}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_AUTOQUAD
+
+// ENUM DEFINITIONS
+
+
+/** @brief Available operating modes/statuses for AutoQuad flight controller.
+ Bitmask up to 32 bits. Low side bits for base modes, high side for
+ additional active features/modifiers/constraints. */
+#ifndef HAVE_ENUM_AUTOQUAD_NAV_STATUS
+#define HAVE_ENUM_AUTOQUAD_NAV_STATUS
+enum AUTOQUAD_NAV_STATUS
+{
+ AQ_NAV_STATUS_INIT=0, /* System is initializing | */
+ AQ_NAV_STATUS_STANDBY=1, /* System is standing by, not active | */
+ AQ_NAV_STATUS_MANUAL=2, /* Stabilized, under full manual control | */
+ AQ_NAV_STATUS_ALTHOLD=4, /* Altitude hold engaged | */
+ AQ_NAV_STATUS_POSHOLD=8, /* Position hold engaged | */
+ AQ_NAV_STATUS_DVH=16, /* Dynamic Velocity Hold is active | */
+ AQ_NAV_STATUS_MISSION=32, /* Autonomous mission execution mode | */
+ AQ_NAV_STATUS_CEILING_REACHED=67108864, /* Craft is at ceiling altitude | */
+ AQ_NAV_STATUS_CEILING=134217728, /* Ceiling altitude is set | */
+ AQ_NAV_STATUS_HF_DYNAMIC=268435456, /* Heading-Free dynamic mode active | */
+ AQ_NAV_STATUS_HF_LOCKED=536870912, /* Heading-Free locked mode active | */
+ AQ_NAV_STATUS_RTH=1073741824, /* Automatic Return to Home is active | */
+ AQ_NAV_STATUS_FAILSAFE=2147483648, /* System is in failsafe recovery mode | */
+ AUTOQUAD_NAV_STATUS_ENUM_END=2147483649, /* | */
+};
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_MAV_CMD
+#define HAVE_ENUM_MAV_CMD
+enum MAV_CMD
+{
+ MAV_CMD_AQ_TELEMETRY=2, /* Start/stop AutoQuad telemetry values stream. |Start or stop (1 or 0)| Stream frequency in us| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_AQ_FOLLOW=3, /* Command AutoQuad to go to a particular place at a set speed. |Latitude| Lontitude| Altitude| Speed| Empty| Empty| Empty| */
+ MAV_CMD_AQ_REQUEST_VERSION=4, /* Request AutoQuad firmware version number. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| */
+ 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| Empty| Empty| */
+ 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| 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| */
+ 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| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
+ 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| */
+ 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| */
+ 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)| */
+ MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
+};
+#endif
+
+#include "../common/common.h"
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 3
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 3
+#endif
+
+// MESSAGE DEFINITIONS
+#include "./mavlink_msg_aq_telemetry_f.h"
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // AUTOQUAD_H
diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h
new file mode 100644
index 000000000..3f80c9a41
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h
@@ -0,0 +1,27 @@
+/** @file
+ * @brief MAVLink comm protocol built from autoquad.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#ifndef MAVLINK_STX
+#define MAVLINK_STX 254
+#endif
+
+#ifndef MAVLINK_ENDIAN
+#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
+#endif
+
+#ifndef MAVLINK_ALIGNED_FIELDS
+#define MAVLINK_ALIGNED_FIELDS 1
+#endif
+
+#ifndef MAVLINK_CRC_EXTRA
+#define MAVLINK_CRC_EXTRA 1
+#endif
+
+#include "version.h"
+#include "autoquad.h"
+
+#endif // MAVLINK_H
diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
new file mode 100644
index 000000000..ed7c86bcb
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
@@ -0,0 +1,617 @@
+// MESSAGE AQ_TELEMETRY_F PACKING
+
+#define MAVLINK_MSG_ID_AQ_TELEMETRY_F 150
+
+typedef struct __mavlink_aq_telemetry_f_t
+{
+ float value1; ///< value1
+ float value2; ///< value2
+ float value3; ///< value3
+ float value4; ///< value4
+ float value5; ///< value5
+ float value6; ///< value6
+ float value7; ///< value7
+ float value8; ///< value8
+ float value9; ///< value9
+ float value10; ///< value10
+ float value11; ///< value11
+ float value12; ///< value12
+ float value13; ///< value13
+ float value14; ///< value14
+ float value15; ///< value15
+ float value16; ///< value16
+ float value17; ///< value17
+ float value18; ///< value18
+ float value19; ///< value19
+ float value20; ///< value20
+ uint16_t Index; ///< Index of message
+} mavlink_aq_telemetry_f_t;
+
+#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN 82
+#define MAVLINK_MSG_ID_150_LEN 82
+
+#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC 241
+#define MAVLINK_MSG_ID_150_CRC 241
+
+
+
+#define MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F { \
+ "AQ_TELEMETRY_F", \
+ 21, \
+ { { "value1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_aq_telemetry_f_t, value1) }, \
+ { "value2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_aq_telemetry_f_t, value2) }, \
+ { "value3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aq_telemetry_f_t, value3) }, \
+ { "value4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aq_telemetry_f_t, value4) }, \
+ { "value5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aq_telemetry_f_t, value5) }, \
+ { "value6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aq_telemetry_f_t, value6) }, \
+ { "value7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aq_telemetry_f_t, value7) }, \
+ { "value8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aq_telemetry_f_t, value8) }, \
+ { "value9", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aq_telemetry_f_t, value9) }, \
+ { "value10", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aq_telemetry_f_t, value10) }, \
+ { "value11", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aq_telemetry_f_t, value11) }, \
+ { "value12", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aq_telemetry_f_t, value12) }, \
+ { "value13", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aq_telemetry_f_t, value13) }, \
+ { "value14", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aq_telemetry_f_t, value14) }, \
+ { "value15", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aq_telemetry_f_t, value15) }, \
+ { "value16", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aq_telemetry_f_t, value16) }, \
+ { "value17", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aq_telemetry_f_t, value17) }, \
+ { "value18", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aq_telemetry_f_t, value18) }, \
+ { "value19", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aq_telemetry_f_t, value19) }, \
+ { "value20", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aq_telemetry_f_t, value20) }, \
+ { "Index", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_aq_telemetry_f_t, Index) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a aq_telemetry_f message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param Index Index of message
+ * @param value1 value1
+ * @param value2 value2
+ * @param value3 value3
+ * @param value4 value4
+ * @param value5 value5
+ * @param value6 value6
+ * @param value7 value7
+ * @param value8 value8
+ * @param value9 value9
+ * @param value10 value10
+ * @param value11 value11
+ * @param value12 value12
+ * @param value13 value13
+ * @param value14 value14
+ * @param value15 value15
+ * @param value16 value16
+ * @param value17 value17
+ * @param value18 value18
+ * @param value19 value19
+ * @param value20 value20
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN];
+ _mav_put_float(buf, 0, value1);
+ _mav_put_float(buf, 4, value2);
+ _mav_put_float(buf, 8, value3);
+ _mav_put_float(buf, 12, value4);
+ _mav_put_float(buf, 16, value5);
+ _mav_put_float(buf, 20, value6);
+ _mav_put_float(buf, 24, value7);
+ _mav_put_float(buf, 28, value8);
+ _mav_put_float(buf, 32, value9);
+ _mav_put_float(buf, 36, value10);
+ _mav_put_float(buf, 40, value11);
+ _mav_put_float(buf, 44, value12);
+ _mav_put_float(buf, 48, value13);
+ _mav_put_float(buf, 52, value14);
+ _mav_put_float(buf, 56, value15);
+ _mav_put_float(buf, 60, value16);
+ _mav_put_float(buf, 64, value17);
+ _mav_put_float(buf, 68, value18);
+ _mav_put_float(buf, 72, value19);
+ _mav_put_float(buf, 76, value20);
+ _mav_put_uint16_t(buf, 80, Index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#else
+ mavlink_aq_telemetry_f_t packet;
+ packet.value1 = value1;
+ packet.value2 = value2;
+ packet.value3 = value3;
+ packet.value4 = value4;
+ packet.value5 = value5;
+ packet.value6 = value6;
+ packet.value7 = value7;
+ packet.value8 = value8;
+ packet.value9 = value9;
+ packet.value10 = value10;
+ packet.value11 = value11;
+ packet.value12 = value12;
+ packet.value13 = value13;
+ packet.value14 = value14;
+ packet.value15 = value15;
+ packet.value16 = value16;
+ packet.value17 = value17;
+ packet.value18 = value18;
+ packet.value19 = value19;
+ packet.value20 = value20;
+ packet.Index = Index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a aq_telemetry_f message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param Index Index of message
+ * @param value1 value1
+ * @param value2 value2
+ * @param value3 value3
+ * @param value4 value4
+ * @param value5 value5
+ * @param value6 value6
+ * @param value7 value7
+ * @param value8 value8
+ * @param value9 value9
+ * @param value10 value10
+ * @param value11 value11
+ * @param value12 value12
+ * @param value13 value13
+ * @param value14 value14
+ * @param value15 value15
+ * @param value16 value16
+ * @param value17 value17
+ * @param value18 value18
+ * @param value19 value19
+ * @param value20 value20
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t Index,float value1,float value2,float value3,float value4,float value5,float value6,float value7,float value8,float value9,float value10,float value11,float value12,float value13,float value14,float value15,float value16,float value17,float value18,float value19,float value20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN];
+ _mav_put_float(buf, 0, value1);
+ _mav_put_float(buf, 4, value2);
+ _mav_put_float(buf, 8, value3);
+ _mav_put_float(buf, 12, value4);
+ _mav_put_float(buf, 16, value5);
+ _mav_put_float(buf, 20, value6);
+ _mav_put_float(buf, 24, value7);
+ _mav_put_float(buf, 28, value8);
+ _mav_put_float(buf, 32, value9);
+ _mav_put_float(buf, 36, value10);
+ _mav_put_float(buf, 40, value11);
+ _mav_put_float(buf, 44, value12);
+ _mav_put_float(buf, 48, value13);
+ _mav_put_float(buf, 52, value14);
+ _mav_put_float(buf, 56, value15);
+ _mav_put_float(buf, 60, value16);
+ _mav_put_float(buf, 64, value17);
+ _mav_put_float(buf, 68, value18);
+ _mav_put_float(buf, 72, value19);
+ _mav_put_float(buf, 76, value20);
+ _mav_put_uint16_t(buf, 80, Index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#else
+ mavlink_aq_telemetry_f_t packet;
+ packet.value1 = value1;
+ packet.value2 = value2;
+ packet.value3 = value3;
+ packet.value4 = value4;
+ packet.value5 = value5;
+ packet.value6 = value6;
+ packet.value7 = value7;
+ packet.value8 = value8;
+ packet.value9 = value9;
+ packet.value10 = value10;
+ packet.value11 = value11;
+ packet.value12 = value12;
+ packet.value13 = value13;
+ packet.value14 = value14;
+ packet.value15 = value15;
+ packet.value16 = value16;
+ packet.value17 = value17;
+ packet.value18 = value18;
+ packet.value19 = value19;
+ packet.value20 = value20;
+ packet.Index = Index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a aq_telemetry_f struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param aq_telemetry_f C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f)
+{
+ return mavlink_msg_aq_telemetry_f_pack(system_id, component_id, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
+}
+
+/**
+ * @brief Encode a aq_telemetry_f struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param aq_telemetry_f C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f)
+{
+ return mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, chan, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
+}
+
+/**
+ * @brief Send a aq_telemetry_f message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param Index Index of message
+ * @param value1 value1
+ * @param value2 value2
+ * @param value3 value3
+ * @param value4 value4
+ * @param value5 value5
+ * @param value6 value6
+ * @param value7 value7
+ * @param value8 value8
+ * @param value9 value9
+ * @param value10 value10
+ * @param value11 value11
+ * @param value12 value12
+ * @param value13 value13
+ * @param value14 value14
+ * @param value15 value15
+ * @param value16 value16
+ * @param value17 value17
+ * @param value18 value18
+ * @param value19 value19
+ * @param value20 value20
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_aq_telemetry_f_send(mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN];
+ _mav_put_float(buf, 0, value1);
+ _mav_put_float(buf, 4, value2);
+ _mav_put_float(buf, 8, value3);
+ _mav_put_float(buf, 12, value4);
+ _mav_put_float(buf, 16, value5);
+ _mav_put_float(buf, 20, value6);
+ _mav_put_float(buf, 24, value7);
+ _mav_put_float(buf, 28, value8);
+ _mav_put_float(buf, 32, value9);
+ _mav_put_float(buf, 36, value10);
+ _mav_put_float(buf, 40, value11);
+ _mav_put_float(buf, 44, value12);
+ _mav_put_float(buf, 48, value13);
+ _mav_put_float(buf, 52, value14);
+ _mav_put_float(buf, 56, value15);
+ _mav_put_float(buf, 60, value16);
+ _mav_put_float(buf, 64, value17);
+ _mav_put_float(buf, 68, value18);
+ _mav_put_float(buf, 72, value19);
+ _mav_put_float(buf, 76, value20);
+ _mav_put_uint16_t(buf, 80, Index);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+#else
+ mavlink_aq_telemetry_f_t packet;
+ packet.value1 = value1;
+ packet.value2 = value2;
+ packet.value3 = value3;
+ packet.value4 = value4;
+ packet.value5 = value5;
+ packet.value6 = value6;
+ packet.value7 = value7;
+ packet.value8 = value8;
+ packet.value9 = value9;
+ packet.value10 = value10;
+ packet.value11 = value11;
+ packet.value12 = value12;
+ packet.value13 = value13;
+ packet.value14 = value14;
+ packet.value15 = value15;
+ packet.value16 = value16;
+ packet.value17 = value17;
+ packet.value18 = value18;
+ packet.value19 = value19;
+ packet.value20 = value20;
+ packet.Index = Index;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+#endif
+}
+
+#endif
+
+// MESSAGE AQ_TELEMETRY_F UNPACKING
+
+
+/**
+ * @brief Get field Index from aq_telemetry_f message
+ *
+ * @return Index of message
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_get_Index(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 80);
+}
+
+/**
+ * @brief Get field value1 from aq_telemetry_f message
+ *
+ * @return value1
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field value2 from aq_telemetry_f message
+ *
+ * @return value2
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field value3 from aq_telemetry_f message
+ *
+ * @return value3
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field value4 from aq_telemetry_f message
+ *
+ * @return value4
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field value5 from aq_telemetry_f message
+ *
+ * @return value5
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value5(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field value6 from aq_telemetry_f message
+ *
+ * @return value6
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value6(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field value7 from aq_telemetry_f message
+ *
+ * @return value7
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value7(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field value8 from aq_telemetry_f message
+ *
+ * @return value8
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value8(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field value9 from aq_telemetry_f message
+ *
+ * @return value9
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value9(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field value10 from aq_telemetry_f message
+ *
+ * @return value10
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value10(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field value11 from aq_telemetry_f message
+ *
+ * @return value11
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value11(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field value12 from aq_telemetry_f message
+ *
+ * @return value12
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value12(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Get field value13 from aq_telemetry_f message
+ *
+ * @return value13
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value13(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 48);
+}
+
+/**
+ * @brief Get field value14 from aq_telemetry_f message
+ *
+ * @return value14
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value14(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 52);
+}
+
+/**
+ * @brief Get field value15 from aq_telemetry_f message
+ *
+ * @return value15
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value15(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 56);
+}
+
+/**
+ * @brief Get field value16 from aq_telemetry_f message
+ *
+ * @return value16
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value16(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 60);
+}
+
+/**
+ * @brief Get field value17 from aq_telemetry_f message
+ *
+ * @return value17
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value17(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 64);
+}
+
+/**
+ * @brief Get field value18 from aq_telemetry_f message
+ *
+ * @return value18
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value18(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 68);
+}
+
+/**
+ * @brief Get field value19 from aq_telemetry_f message
+ *
+ * @return value19
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value19(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 72);
+}
+
+/**
+ * @brief Get field value20 from aq_telemetry_f message
+ *
+ * @return value20
+ */
+static inline float mavlink_msg_aq_telemetry_f_get_value20(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 76);
+}
+
+/**
+ * @brief Decode a aq_telemetry_f message into a struct
+ *
+ * @param msg The message to decode
+ * @param aq_telemetry_f C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_aq_telemetry_f_decode(const mavlink_message_t* msg, mavlink_aq_telemetry_f_t* aq_telemetry_f)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ aq_telemetry_f->value1 = mavlink_msg_aq_telemetry_f_get_value1(msg);
+ aq_telemetry_f->value2 = mavlink_msg_aq_telemetry_f_get_value2(msg);
+ aq_telemetry_f->value3 = mavlink_msg_aq_telemetry_f_get_value3(msg);
+ aq_telemetry_f->value4 = mavlink_msg_aq_telemetry_f_get_value4(msg);
+ aq_telemetry_f->value5 = mavlink_msg_aq_telemetry_f_get_value5(msg);
+ aq_telemetry_f->value6 = mavlink_msg_aq_telemetry_f_get_value6(msg);
+ aq_telemetry_f->value7 = mavlink_msg_aq_telemetry_f_get_value7(msg);
+ aq_telemetry_f->value8 = mavlink_msg_aq_telemetry_f_get_value8(msg);
+ aq_telemetry_f->value9 = mavlink_msg_aq_telemetry_f_get_value9(msg);
+ aq_telemetry_f->value10 = mavlink_msg_aq_telemetry_f_get_value10(msg);
+ aq_telemetry_f->value11 = mavlink_msg_aq_telemetry_f_get_value11(msg);
+ aq_telemetry_f->value12 = mavlink_msg_aq_telemetry_f_get_value12(msg);
+ aq_telemetry_f->value13 = mavlink_msg_aq_telemetry_f_get_value13(msg);
+ aq_telemetry_f->value14 = mavlink_msg_aq_telemetry_f_get_value14(msg);
+ aq_telemetry_f->value15 = mavlink_msg_aq_telemetry_f_get_value15(msg);
+ aq_telemetry_f->value16 = mavlink_msg_aq_telemetry_f_get_value16(msg);
+ aq_telemetry_f->value17 = mavlink_msg_aq_telemetry_f_get_value17(msg);
+ aq_telemetry_f->value18 = mavlink_msg_aq_telemetry_f_get_value18(msg);
+ aq_telemetry_f->value19 = mavlink_msg_aq_telemetry_f_get_value19(msg);
+ aq_telemetry_f->value20 = mavlink_msg_aq_telemetry_f_get_value20(msg);
+ aq_telemetry_f->Index = mavlink_msg_aq_telemetry_f_get_Index(msg);
+#else
+ memcpy(aq_telemetry_f, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h
new file mode 100644
index 000000000..4eafe7be5
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h
@@ -0,0 +1,118 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from autoquad.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef AUTOQUAD_TESTSUITE_H
+#define AUTOQUAD_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_autoquad(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_common(system_id, component_id, last_msg);
+ mavlink_test_autoquad(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../common/testsuite.h"
+
+
+static void mavlink_test_aq_telemetry_f(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_aq_telemetry_f_t packet_in = {
+ 17.0,
+ }45.0,
+ }73.0,
+ }101.0,
+ }129.0,
+ }157.0,
+ }185.0,
+ }213.0,
+ }241.0,
+ }269.0,
+ }297.0,
+ }325.0,
+ }353.0,
+ }381.0,
+ }409.0,
+ }437.0,
+ }465.0,
+ }493.0,
+ }521.0,
+ }549.0,
+ }21395,
+ };
+ mavlink_aq_telemetry_f_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.value1 = packet_in.value1;
+ packet1.value2 = packet_in.value2;
+ packet1.value3 = packet_in.value3;
+ packet1.value4 = packet_in.value4;
+ packet1.value5 = packet_in.value5;
+ packet1.value6 = packet_in.value6;
+ packet1.value7 = packet_in.value7;
+ packet1.value8 = packet_in.value8;
+ packet1.value9 = packet_in.value9;
+ packet1.value10 = packet_in.value10;
+ packet1.value11 = packet_in.value11;
+ packet1.value12 = packet_in.value12;
+ packet1.value13 = packet_in.value13;
+ packet1.value14 = packet_in.value14;
+ packet1.value15 = packet_in.value15;
+ packet1.value16 = packet_in.value16;
+ packet1.value17 = packet_in.value17;
+ packet1.value18 = packet_in.value18;
+ packet1.value19 = packet_in.value19;
+ packet1.value20 = packet_in.value20;
+ packet1.Index = packet_in.Index;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aq_telemetry_f_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_aq_telemetry_f_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aq_telemetry_f_pack(system_id, component_id, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 );
+ mavlink_msg_aq_telemetry_f_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 );
+ mavlink_msg_aq_telemetry_f_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_aq_telemetry_f_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aq_telemetry_f_send(MAVLINK_COMM_1 , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 );
+ mavlink_msg_aq_telemetry_f_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_autoquad(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_aq_telemetry_f(system_id, component_id, last_msg);
+}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // AUTOQUAD_TESTSUITE_H
diff --git a/mavlink/include/mavlink/v1.0/autoquad/version.h b/mavlink/include/mavlink/v1.0/autoquad/version.h
new file mode 100644
index 000000000..53e781807
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/autoquad/version.h
@@ -0,0 +1,12 @@
+/** @file
+ * @brief MAVLink comm protocol built from autoquad.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_VERSION_H
+#define MAVLINK_VERSION_H
+
+#define MAVLINK_BUILD_DATE "Mon Dec 16 09:03:20 2013"
+#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
+
+#endif // MAVLINK_VERSION_H