Emaxx Navigation Group / mavlink_emaxx

Dependents:   Madpulse_Speed_Control_temp Madpulse_Speed_Control_Students

Files at this revision

API Documentation at this revision

Comitter:
jdawkins
Date:
Fri Jan 20 13:20:58 2017 +0000
Child:
1:7e9af9a921f7
Commit message:
Initial Commit of Mavlink Messages for Emaxx Board custom messages for decawave ranging and bno055;

Changed in this revision

checksum.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/emaxx_board.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_attitude.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_attitude_quaternion.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_fused_imu.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_gps_raw_int.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_local_position_ned.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_range_to_node.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_scaled_imu.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_sys_status.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/mavlink_msg_system_time.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/testsuite.h Show annotated file Show diff for this revision Revisions of this file
emaxx_board/version.h Show annotated file Show diff for this revision Revisions of this file
mavlink_conversions.h Show annotated file Show diff for this revision Revisions of this file
mavlink_helpers.h Show annotated file Show diff for this revision Revisions of this file
mavlink_types.h Show annotated file Show diff for this revision Revisions of this file
protocol.h Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/checksum.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,97 @@
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef _CHECKSUM_H_
+#define _CHECKSUM_H_
+
+// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
+#if (defined _MSC_VER) && (_MSC_VER < 1600)
+#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
+#endif
+
+#include <stdint.h>
+
+/**
+ *
+ *  CALCULATE THE CHECKSUM
+ *
+ */
+
+#define X25_INIT_CRC 0xffff
+#define X25_VALIDATE_CRC 0xf0b8
+
+#ifndef HAVE_CRC_ACCUMULATE
+/**
+ * @brief Accumulate the X.25 CRC by adding one char at a time.
+ *
+ * The checksum function adds the hash of one char at a time to the
+ * 16 bit checksum (uint16_t).
+ *
+ * @param data new char to hash
+ * @param crcAccum the already accumulated checksum
+ **/
+static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
+{
+        /*Accumulate one byte of data into the CRC*/
+        uint8_t tmp;
+
+        tmp = data ^ (uint8_t)(*crcAccum &0xff);
+        tmp ^= (tmp<<4);
+        *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
+}
+#endif
+
+
+/**
+ * @brief Initiliaze the buffer for the X.25 CRC
+ *
+ * @param crcAccum the 16 bit X.25 CRC
+ */
+static inline void crc_init(uint16_t* crcAccum)
+{
+        *crcAccum = X25_INIT_CRC;
+}
+
+
+/**
+ * @brief Calculates the X.25 checksum on a byte buffer
+ *
+ * @param  pBuffer buffer containing the byte array to hash
+ * @param  length  length of the byte array
+ * @return the checksum over the buffer bytes
+ **/
+static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
+{
+        uint16_t crcTmp;
+        crc_init(&crcTmp);
+	while (length--) {
+                crc_accumulate(*pBuffer++, &crcTmp);
+        }
+        return crcTmp;
+}
+
+
+/**
+ * @brief Accumulate the X.25 CRC by adding an array of bytes
+ *
+ * The checksum function adds the hash of one char at a time to the
+ * 16 bit checksum (uint16_t).
+ *
+ * @param data new bytes to hash
+ * @param crcAccum the already accumulated checksum
+ **/
+static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
+{
+	const uint8_t *p = (const uint8_t *)pBuffer;
+	while (length--) {
+                crc_accumulate(*p++, crcAccum);
+        }
+}
+
+#endif /* _CHECKSUM_H_ */
+
+#ifdef __cplusplus
+}
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/emaxx_board.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,175 @@
+/** @file
+ *  @brief MAVLink comm protocol generated from emaxx_board.xml
+ *  @see http://mavlink.org
+ */
+#pragma once
+#ifndef MAVLINK_EMAXX_BOARD_H
+#define MAVLINK_EMAXX_BOARD_H
+
+#ifndef MAVLINK_H
+    #error Wrong include order: MAVLINK_EMAXX_BOARD.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.
+#endif
+
+#undef MAVLINK_THIS_XML_IDX
+#define MAVLINK_THIS_XML_IDX 0
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 0, 22, 0, 0, 0, 28, 32, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 0, 170, 0, 0, 0, 39, 246, 185, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_EMAXX_BOARD
+
+// ENUM DEFINITIONS
+
+
+/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
+#ifndef HAVE_ENUM_MAV_AUTOPILOT
+#define HAVE_ENUM_MAV_AUTOPILOT
+typedef enum MAV_AUTOPILOT
+{
+   MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
+   MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */
+   MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
+   MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */
+   MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
+   MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
+   MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
+   MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
+   MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
+   MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
+   MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
+   MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
+   MAV_AUTOPILOT_ENUM_END=12, /*  | */
+} MAV_AUTOPILOT;
+#endif
+
+/** @brief  */
+#ifndef HAVE_ENUM_MAV_TYPE
+#define HAVE_ENUM_MAV_TYPE
+typedef enum MAV_TYPE
+{
+   MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
+   MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
+   MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
+   MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
+   MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
+   MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
+   MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
+   MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
+   MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
+   MAV_TYPE_ROCKET=9, /* Rocket | */
+   MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
+   MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
+   MAV_TYPE_SUBMARINE=12, /* Submarine | */
+   MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
+   MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
+   MAV_TYPE_TRICOPTER=15, /* Octorotor | */
+   MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
+   MAV_TYPE_ENUM_END=17, /*  | */
+} MAV_TYPE;
+#endif
+
+/** @brief These flags encode the MAV mode. */
+#ifndef HAVE_ENUM_MAV_MODE_FLAG
+#define HAVE_ENUM_MAV_MODE_FLAG
+typedef enum MAV_MODE_FLAG
+{
+   MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
+   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. | */
+   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. | */
+   MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
+   MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
+   MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
+   MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
+   MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
+   MAV_MODE_FLAG_ENUM_END=129, /*  | */
+} MAV_MODE_FLAG;
+#endif
+
+/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */
+#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
+#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
+typedef enum MAV_MODE_FLAG_DECODE_POSITION
+{
+   MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
+   MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
+   MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit:   00000100 | */
+   MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit:  00001000 | */
+   MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
+   MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit:  00100000 | */
+   MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
+   MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit:  10000000 | */
+   MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /*  | */
+} MAV_MODE_FLAG_DECODE_POSITION;
+#endif
+
+/** @brief  */
+#ifndef HAVE_ENUM_MAV_STATE
+#define HAVE_ENUM_MAV_STATE
+typedef enum MAV_STATE
+{
+   MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
+   MAV_STATE_BOOT=1, /* System is booting up. | */
+   MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
+   MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
+   MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
+   MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
+   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. | */
+   MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
+   MAV_STATE_ENUM_END=8, /*  | */
+} MAV_STATE;
+#endif
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+// MESSAGE DEFINITIONS
+#include "./mavlink_msg_heartbeat.h"
+#include "./mavlink_msg_sys_status.h"
+#include "./mavlink_msg_system_time.h"
+#include "./mavlink_msg_gps_raw_int.h"
+#include "./mavlink_msg_scaled_imu.h"
+#include "./mavlink_msg_attitude.h"
+#include "./mavlink_msg_attitude_quaternion.h"
+#include "./mavlink_msg_local_position_ned.h"
+#include "./mavlink_msg_range_to_node.h"
+#include "./mavlink_msg_fused_imu.h"
+
+// base include
+
+
+#undef MAVLINK_THIS_XML_IDX
+#define MAVLINK_THIS_XML_IDX 0
+
+#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
+# 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}}}, {"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_GPS_RAW_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SCALED_IMU, {"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, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {"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}}}, {"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_RANGE_TO_NODE, MAVLINK_MESSAGE_INFO_FUSED_IMU, {"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}}}, {"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}}}}
+# if MAVLINK_COMMAND_24BIT
+#  include "../mavlink_get_info.h"
+# endif
+#endif
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // MAVLINK_EMAXX_BOARD_H
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,35 @@
+/** @file
+ *  @brief MAVLink comm protocol built from emaxx_board.xml
+ *  @see http://mavlink.org
+ */
+#pragma once
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#define MAVLINK_PRIMARY_XML_IDX 0
+
+#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
+
+#ifndef MAVLINK_COMMAND_24BIT
+#define MAVLINK_COMMAND_24BIT 0
+#endif
+
+#include "version.h"
+#include "emaxx_board.h"
+
+#endif // MAVLINK_H
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_attitude.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,364 @@
+#pragma once
+// MESSAGE ATTITUDE PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE 30
+
+MAVPACKED(
+typedef struct __mavlink_attitude_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ float roll; /*< Roll angle (rad, -pi..+pi)*/
+ float pitch; /*< Pitch angle (rad, -pi..+pi)*/
+ float yaw; /*< Yaw angle (rad, -pi..+pi)*/
+ float rollspeed; /*< Roll angular speed (rad/s)*/
+ float pitchspeed; /*< Pitch angular speed (rad/s)*/
+ float yawspeed; /*< Yaw angular speed (rad/s)*/
+}) mavlink_attitude_t;
+
+#define MAVLINK_MSG_ID_ATTITUDE_LEN 28
+#define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28
+#define MAVLINK_MSG_ID_30_LEN 28
+#define MAVLINK_MSG_ID_30_MIN_LEN 28
+
+#define MAVLINK_MSG_ID_ATTITUDE_CRC 39
+#define MAVLINK_MSG_ID_30_CRC 39
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ATTITUDE { \
+    30, \
+    "ATTITUDE", \
+    7, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
+         { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
+         { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
+         { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ATTITUDE { \
+    "ATTITUDE", \
+    7, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
+         { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
+         { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
+         { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a attitude 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, roll);
+    _mav_put_float(buf, 8, pitch);
+    _mav_put_float(buf, 12, yaw);
+    _mav_put_float(buf, 16, rollspeed);
+    _mav_put_float(buf, 20, pitchspeed);
+    _mav_put_float(buf, 24, yawspeed);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#else
+    mavlink_attitude_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+}
+
+/**
+ * @brief Pack a attitude 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, roll);
+    _mav_put_float(buf, 8, pitch);
+    _mav_put_float(buf, 12, yaw);
+    _mav_put_float(buf, 16, rollspeed);
+    _mav_put_float(buf, 20, pitchspeed);
+    _mav_put_float(buf, 24, yawspeed);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#else
+    mavlink_attitude_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+}
+
+/**
+ * @brief Encode a attitude 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 attitude C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
+{
+    return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
+}
+
+/**
+ * @brief Encode a attitude 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 attitude C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
+{
+    return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
+}
+
+/**
+ * @brief Send a attitude message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, roll);
+    _mav_put_float(buf, 8, pitch);
+    _mav_put_float(buf, 12, yaw);
+    _mav_put_float(buf, 16, rollspeed);
+    _mav_put_float(buf, 20, pitchspeed);
+    _mav_put_float(buf, 24, yawspeed);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#else
+    mavlink_attitude_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a attitude message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)attitude, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, roll);
+    _mav_put_float(buf, 8, pitch);
+    _mav_put_float(buf, 12, yaw);
+    _mav_put_float(buf, 16, rollspeed);
+    _mav_put_float(buf, 20, pitchspeed);
+    _mav_put_float(buf, 24, yawspeed);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#else
+    mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->roll = roll;
+    packet->pitch = pitch;
+    packet->yaw = yaw;
+    packet->rollspeed = rollspeed;
+    packet->pitchspeed = pitchspeed;
+    packet->yawspeed = yawspeed;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ATTITUDE UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from attitude message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field roll from attitude message
+ *
+ * @return Roll angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Get field pitch from attitude message
+ *
+ * @return Pitch angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field yaw from attitude message
+ *
+ * @return Yaw angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field rollspeed from attitude message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field pitchspeed from attitude message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field yawspeed from attitude message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Decode a attitude message into a struct
+ *
+ * @param msg The message to decode
+ * @param attitude C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
+    attitude->roll = mavlink_msg_attitude_get_roll(msg);
+    attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
+    attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
+    attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
+    attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
+    attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN;
+        memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN);
+    memcpy(attitude, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_attitude_quaternion.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,389 @@
+#pragma once
+// MESSAGE ATTITUDE_QUATERNION PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
+
+MAVPACKED(
+typedef struct __mavlink_attitude_quaternion_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ float q1; /*< Quaternion component 1, w (1 in null-rotation)*/
+ float q2; /*< Quaternion component 2, x (0 in null-rotation)*/
+ float q3; /*< Quaternion component 3, y (0 in null-rotation)*/
+ float q4; /*< Quaternion component 4, z (0 in null-rotation)*/
+ float rollspeed; /*< Roll angular speed (rad/s)*/
+ float pitchspeed; /*< Pitch angular speed (rad/s)*/
+ float yawspeed; /*< Yaw angular speed (rad/s)*/
+}) mavlink_attitude_quaternion_t;
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
+#define MAVLINK_MSG_ID_31_LEN 32
+#define MAVLINK_MSG_ID_31_MIN_LEN 32
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
+#define MAVLINK_MSG_ID_31_CRC 246
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
+    31, \
+    "ATTITUDE_QUATERNION", \
+    8, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
+         { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
+         { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
+         { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
+         { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
+         { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
+         { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
+         { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
+    "ATTITUDE_QUATERNION", \
+    8, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
+         { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
+         { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
+         { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
+         { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
+         { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
+         { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
+         { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a attitude_quaternion 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, q1);
+    _mav_put_float(buf, 8, q2);
+    _mav_put_float(buf, 12, q3);
+    _mav_put_float(buf, 16, q4);
+    _mav_put_float(buf, 20, rollspeed);
+    _mav_put_float(buf, 24, pitchspeed);
+    _mav_put_float(buf, 28, yawspeed);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#else
+    mavlink_attitude_quaternion_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.q1 = q1;
+    packet.q2 = q2;
+    packet.q3 = q3;
+    packet.q4 = q4;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+}
+
+/**
+ * @brief Pack a attitude_quaternion 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, q1);
+    _mav_put_float(buf, 8, q2);
+    _mav_put_float(buf, 12, q3);
+    _mav_put_float(buf, 16, q4);
+    _mav_put_float(buf, 20, rollspeed);
+    _mav_put_float(buf, 24, pitchspeed);
+    _mav_put_float(buf, 28, yawspeed);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#else
+    mavlink_attitude_quaternion_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.q1 = q1;
+    packet.q2 = q2;
+    packet.q3 = q3;
+    packet.q4 = q4;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+}
+
+/**
+ * @brief Encode a attitude_quaternion 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 attitude_quaternion C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
+{
+    return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
+}
+
+/**
+ * @brief Encode a attitude_quaternion 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 attitude_quaternion C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
+{
+    return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
+}
+
+/**
+ * @brief Send a attitude_quaternion message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, q1);
+    _mav_put_float(buf, 8, q2);
+    _mav_put_float(buf, 12, q3);
+    _mav_put_float(buf, 16, q4);
+    _mav_put_float(buf, 20, rollspeed);
+    _mav_put_float(buf, 24, pitchspeed);
+    _mav_put_float(buf, 28, yawspeed);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#else
+    mavlink_attitude_quaternion_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.q1 = q1;
+    packet.q2 = q2;
+    packet.q3 = q3;
+    packet.q4 = q4;
+    packet.rollspeed = rollspeed;
+    packet.pitchspeed = pitchspeed;
+    packet.yawspeed = yawspeed;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a attitude_quaternion message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_attitude_quaternion_send(chan, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, q1);
+    _mav_put_float(buf, 8, q2);
+    _mav_put_float(buf, 12, q3);
+    _mav_put_float(buf, 16, q4);
+    _mav_put_float(buf, 20, rollspeed);
+    _mav_put_float(buf, 24, pitchspeed);
+    _mav_put_float(buf, 28, yawspeed);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#else
+    mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->q1 = q1;
+    packet->q2 = q2;
+    packet->q3 = q3;
+    packet->q4 = q4;
+    packet->rollspeed = rollspeed;
+    packet->pitchspeed = pitchspeed;
+    packet->yawspeed = yawspeed;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ATTITUDE_QUATERNION UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from attitude_quaternion message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field q1 from attitude_quaternion message
+ *
+ * @return Quaternion component 1, w (1 in null-rotation)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Get field q2 from attitude_quaternion message
+ *
+ * @return Quaternion component 2, x (0 in null-rotation)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field q3 from attitude_quaternion message
+ *
+ * @return Quaternion component 3, y (0 in null-rotation)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field q4 from attitude_quaternion message
+ *
+ * @return Quaternion component 4, z (0 in null-rotation)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field rollspeed from attitude_quaternion message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field pitchspeed from attitude_quaternion message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field yawspeed from attitude_quaternion message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Decode a attitude_quaternion message into a struct
+ *
+ * @param msg The message to decode
+ * @param attitude_quaternion C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
+    attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg);
+    attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg);
+    attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg);
+    attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg);
+    attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg);
+    attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg);
+    attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN;
+        memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+    memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_fused_imu.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,439 @@
+#pragma once
+// MESSAGE FUSED_IMU PACKING
+
+#define MAVLINK_MSG_ID_FUSED_IMU 151
+
+MAVPACKED(
+typedef struct __mavlink_fused_imu_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ float accel_x; /*< X acceleration (m/s^2)*/
+ float accel_y; /*< Y acceleration (m/s^2)*/
+ float accel_z; /*< Z acceleration (m/s^2)*/
+ float gyro_x; /*< Roll angular speed (rad/s)*/
+ float gyro_y; /*< Pitch angular speed (rad/s)*/
+ float gyro_z; /*< Yaw angular speed (rad/s)*/
+ float roll; /*< Roll angle (rad, -pi..+pi)*/
+ float pitch; /*< Pitch angle (rad, -pi..+pi)*/
+ float yaw; /*< Yaw angle (rad, -pi..+pi)*/
+}) mavlink_fused_imu_t;
+
+#define MAVLINK_MSG_ID_FUSED_IMU_LEN 40
+#define MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN 40
+#define MAVLINK_MSG_ID_151_LEN 40
+#define MAVLINK_MSG_ID_151_MIN_LEN 40
+
+#define MAVLINK_MSG_ID_FUSED_IMU_CRC 218
+#define MAVLINK_MSG_ID_151_CRC 218
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_FUSED_IMU { \
+    151, \
+    "FUSED_IMU", \
+    10, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fused_imu_t, time_boot_ms) }, \
+         { "accel_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fused_imu_t, accel_x) }, \
+         { "accel_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_fused_imu_t, accel_y) }, \
+         { "accel_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_fused_imu_t, accel_z) }, \
+         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_fused_imu_t, gyro_x) }, \
+         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_fused_imu_t, gyro_y) }, \
+         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_fused_imu_t, gyro_z) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_fused_imu_t, roll) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_fused_imu_t, pitch) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_fused_imu_t, yaw) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_FUSED_IMU { \
+    "FUSED_IMU", \
+    10, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fused_imu_t, time_boot_ms) }, \
+         { "accel_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fused_imu_t, accel_x) }, \
+         { "accel_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_fused_imu_t, accel_y) }, \
+         { "accel_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_fused_imu_t, accel_z) }, \
+         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_fused_imu_t, gyro_x) }, \
+         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_fused_imu_t, gyro_y) }, \
+         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_fused_imu_t, gyro_z) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_fused_imu_t, roll) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_fused_imu_t, pitch) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_fused_imu_t, yaw) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a fused_imu 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param accel_x X acceleration (m/s^2)
+ * @param accel_y Y acceleration (m/s^2)
+ * @param accel_z Z acceleration (m/s^2)
+ * @param gyro_x Roll angular speed (rad/s)
+ * @param gyro_y Pitch angular speed (rad/s)
+ * @param gyro_z Yaw angular speed (rad/s)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fused_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, float accel_x, float accel_y, float accel_z, float gyro_x, float gyro_y, float gyro_z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_FUSED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, accel_x);
+    _mav_put_float(buf, 8, accel_y);
+    _mav_put_float(buf, 12, accel_z);
+    _mav_put_float(buf, 16, gyro_x);
+    _mav_put_float(buf, 20, gyro_y);
+    _mav_put_float(buf, 24, gyro_z);
+    _mav_put_float(buf, 28, roll);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, yaw);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FUSED_IMU_LEN);
+#else
+    mavlink_fused_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.accel_x = accel_x;
+    packet.accel_y = accel_y;
+    packet.accel_z = accel_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FUSED_IMU_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_FUSED_IMU;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+}
+
+/**
+ * @brief Pack a fused_imu 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param accel_x X acceleration (m/s^2)
+ * @param accel_y Y acceleration (m/s^2)
+ * @param accel_z Z acceleration (m/s^2)
+ * @param gyro_x Roll angular speed (rad/s)
+ * @param gyro_y Pitch angular speed (rad/s)
+ * @param gyro_z Yaw angular speed (rad/s)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fused_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,float accel_x,float accel_y,float accel_z,float gyro_x,float gyro_y,float gyro_z,float roll,float pitch,float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_FUSED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, accel_x);
+    _mav_put_float(buf, 8, accel_y);
+    _mav_put_float(buf, 12, accel_z);
+    _mav_put_float(buf, 16, gyro_x);
+    _mav_put_float(buf, 20, gyro_y);
+    _mav_put_float(buf, 24, gyro_z);
+    _mav_put_float(buf, 28, roll);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, yaw);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FUSED_IMU_LEN);
+#else
+    mavlink_fused_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.accel_x = accel_x;
+    packet.accel_y = accel_y;
+    packet.accel_z = accel_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FUSED_IMU_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_FUSED_IMU;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+}
+
+/**
+ * @brief Encode a fused_imu 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 fused_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fused_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fused_imu_t* fused_imu)
+{
+    return mavlink_msg_fused_imu_pack(system_id, component_id, msg, fused_imu->time_boot_ms, fused_imu->accel_x, fused_imu->accel_y, fused_imu->accel_z, fused_imu->gyro_x, fused_imu->gyro_y, fused_imu->gyro_z, fused_imu->roll, fused_imu->pitch, fused_imu->yaw);
+}
+
+/**
+ * @brief Encode a fused_imu 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 fused_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fused_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fused_imu_t* fused_imu)
+{
+    return mavlink_msg_fused_imu_pack_chan(system_id, component_id, chan, msg, fused_imu->time_boot_ms, fused_imu->accel_x, fused_imu->accel_y, fused_imu->accel_z, fused_imu->gyro_x, fused_imu->gyro_y, fused_imu->gyro_z, fused_imu->roll, fused_imu->pitch, fused_imu->yaw);
+}
+
+/**
+ * @brief Send a fused_imu message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param accel_x X acceleration (m/s^2)
+ * @param accel_y Y acceleration (m/s^2)
+ * @param accel_z Z acceleration (m/s^2)
+ * @param gyro_x Roll angular speed (rad/s)
+ * @param gyro_y Pitch angular speed (rad/s)
+ * @param gyro_z Yaw angular speed (rad/s)
+ * @param roll Roll angle (rad, -pi..+pi)
+ * @param pitch Pitch angle (rad, -pi..+pi)
+ * @param yaw Yaw angle (rad, -pi..+pi)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_fused_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, float accel_x, float accel_y, float accel_z, float gyro_x, float gyro_y, float gyro_z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_FUSED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, accel_x);
+    _mav_put_float(buf, 8, accel_y);
+    _mav_put_float(buf, 12, accel_z);
+    _mav_put_float(buf, 16, gyro_x);
+    _mav_put_float(buf, 20, gyro_y);
+    _mav_put_float(buf, 24, gyro_z);
+    _mav_put_float(buf, 28, roll);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, yaw);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FUSED_IMU, buf, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+#else
+    mavlink_fused_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.accel_x = accel_x;
+    packet.accel_y = accel_y;
+    packet.accel_z = accel_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FUSED_IMU, (const char *)&packet, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+#endif
+}
+
+/**
+ * @brief Send a fused_imu message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_fused_imu_send_struct(mavlink_channel_t chan, const mavlink_fused_imu_t* fused_imu)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_fused_imu_send(chan, fused_imu->time_boot_ms, fused_imu->accel_x, fused_imu->accel_y, fused_imu->accel_z, fused_imu->gyro_x, fused_imu->gyro_y, fused_imu->gyro_z, fused_imu->roll, fused_imu->pitch, fused_imu->yaw);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FUSED_IMU, (const char *)fused_imu, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_FUSED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_fused_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, float accel_x, float accel_y, float accel_z, float gyro_x, float gyro_y, float gyro_z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, accel_x);
+    _mav_put_float(buf, 8, accel_y);
+    _mav_put_float(buf, 12, accel_z);
+    _mav_put_float(buf, 16, gyro_x);
+    _mav_put_float(buf, 20, gyro_y);
+    _mav_put_float(buf, 24, gyro_z);
+    _mav_put_float(buf, 28, roll);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, yaw);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FUSED_IMU, buf, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+#else
+    mavlink_fused_imu_t *packet = (mavlink_fused_imu_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->accel_x = accel_x;
+    packet->accel_y = accel_y;
+    packet->accel_z = accel_z;
+    packet->gyro_x = gyro_x;
+    packet->gyro_y = gyro_y;
+    packet->gyro_z = gyro_z;
+    packet->roll = roll;
+    packet->pitch = pitch;
+    packet->yaw = yaw;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FUSED_IMU, (const char *)packet, MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN, MAVLINK_MSG_ID_FUSED_IMU_LEN, MAVLINK_MSG_ID_FUSED_IMU_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FUSED_IMU UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from fused_imu message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_fused_imu_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field accel_x from fused_imu message
+ *
+ * @return X acceleration (m/s^2)
+ */
+static inline float mavlink_msg_fused_imu_get_accel_x(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Get field accel_y from fused_imu message
+ *
+ * @return Y acceleration (m/s^2)
+ */
+static inline float mavlink_msg_fused_imu_get_accel_y(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field accel_z from fused_imu message
+ *
+ * @return Z acceleration (m/s^2)
+ */
+static inline float mavlink_msg_fused_imu_get_accel_z(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field gyro_x from fused_imu message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_fused_imu_get_gyro_x(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field gyro_y from fused_imu message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_fused_imu_get_gyro_y(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field gyro_z from fused_imu message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_fused_imu_get_gyro_z(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field roll from fused_imu message
+ *
+ * @return Roll angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_fused_imu_get_roll(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field pitch from fused_imu message
+ *
+ * @return Pitch angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_fused_imu_get_pitch(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field yaw from fused_imu message
+ *
+ * @return Yaw angle (rad, -pi..+pi)
+ */
+static inline float mavlink_msg_fused_imu_get_yaw(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  36);
+}
+
+/**
+ * @brief Decode a fused_imu message into a struct
+ *
+ * @param msg The message to decode
+ * @param fused_imu C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_fused_imu_decode(const mavlink_message_t* msg, mavlink_fused_imu_t* fused_imu)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    fused_imu->time_boot_ms = mavlink_msg_fused_imu_get_time_boot_ms(msg);
+    fused_imu->accel_x = mavlink_msg_fused_imu_get_accel_x(msg);
+    fused_imu->accel_y = mavlink_msg_fused_imu_get_accel_y(msg);
+    fused_imu->accel_z = mavlink_msg_fused_imu_get_accel_z(msg);
+    fused_imu->gyro_x = mavlink_msg_fused_imu_get_gyro_x(msg);
+    fused_imu->gyro_y = mavlink_msg_fused_imu_get_gyro_y(msg);
+    fused_imu->gyro_z = mavlink_msg_fused_imu_get_gyro_z(msg);
+    fused_imu->roll = mavlink_msg_fused_imu_get_roll(msg);
+    fused_imu->pitch = mavlink_msg_fused_imu_get_pitch(msg);
+    fused_imu->yaw = mavlink_msg_fused_imu_get_yaw(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_FUSED_IMU_LEN? msg->len : MAVLINK_MSG_ID_FUSED_IMU_LEN;
+        memset(fused_imu, 0, MAVLINK_MSG_ID_FUSED_IMU_LEN);
+    memcpy(fused_imu, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_gps_raw_int.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,439 @@
+#pragma once
+// MESSAGE GPS_RAW_INT PACKING
+
+#define MAVLINK_MSG_ID_GPS_RAW_INT 24
+
+MAVPACKED(
+typedef struct __mavlink_gps_raw_int_t {
+ uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
+ int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
+ int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
+ int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/
+ uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
+ uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
+ uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/
+ uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
+ uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/
+ uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
+}) mavlink_gps_raw_int_t;
+
+#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
+#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
+#define MAVLINK_MSG_ID_24_LEN 30
+#define MAVLINK_MSG_ID_24_MIN_LEN 30
+
+#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
+#define MAVLINK_MSG_ID_24_CRC 24
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
+    24, \
+    "GPS_RAW_INT", \
+    10, \
+    {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
+         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
+         { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
+         { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
+         { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
+         { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
+         { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
+         { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
+    "GPS_RAW_INT", \
+    10, \
+    {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
+         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
+         { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
+         { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
+         { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
+         { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
+         { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
+         { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a gps_raw_int 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 time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type See the GPS_FIX_TYPE enum.
+ * @param lat Latitude (WGS84), in degrees * 1E7
+ * @param lon Longitude (WGS84), in degrees * 1E7
+ * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
+ * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ * @param satellites_visible Number of satellites visible. If unknown, set to 255
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
+    _mav_put_uint64_t(buf, 0, time_usec);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_int32_t(buf, 16, alt);
+    _mav_put_uint16_t(buf, 20, eph);
+    _mav_put_uint16_t(buf, 22, epv);
+    _mav_put_uint16_t(buf, 24, vel);
+    _mav_put_uint16_t(buf, 26, cog);
+    _mav_put_uint8_t(buf, 28, fix_type);
+    _mav_put_uint8_t(buf, 29, satellites_visible);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#else
+    mavlink_gps_raw_int_t packet;
+    packet.time_usec = time_usec;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.alt = alt;
+    packet.eph = eph;
+    packet.epv = epv;
+    packet.vel = vel;
+    packet.cog = cog;
+    packet.fix_type = fix_type;
+    packet.satellites_visible = satellites_visible;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+}
+
+/**
+ * @brief Pack a gps_raw_int 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 time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type See the GPS_FIX_TYPE enum.
+ * @param lat Latitude (WGS84), in degrees * 1E7
+ * @param lon Longitude (WGS84), in degrees * 1E7
+ * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
+ * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ * @param satellites_visible Number of satellites visible. If unknown, set to 255
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
+    _mav_put_uint64_t(buf, 0, time_usec);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_int32_t(buf, 16, alt);
+    _mav_put_uint16_t(buf, 20, eph);
+    _mav_put_uint16_t(buf, 22, epv);
+    _mav_put_uint16_t(buf, 24, vel);
+    _mav_put_uint16_t(buf, 26, cog);
+    _mav_put_uint8_t(buf, 28, fix_type);
+    _mav_put_uint8_t(buf, 29, satellites_visible);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#else
+    mavlink_gps_raw_int_t packet;
+    packet.time_usec = time_usec;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.alt = alt;
+    packet.eph = eph;
+    packet.epv = epv;
+    packet.vel = vel;
+    packet.cog = cog;
+    packet.fix_type = fix_type;
+    packet.satellites_visible = satellites_visible;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+}
+
+/**
+ * @brief Encode a gps_raw_int 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 gps_raw_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
+{
+    return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
+}
+
+/**
+ * @brief Encode a gps_raw_int 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 gps_raw_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
+{
+    return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
+}
+
+/**
+ * @brief Send a gps_raw_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type See the GPS_FIX_TYPE enum.
+ * @param lat Latitude (WGS84), in degrees * 1E7
+ * @param lon Longitude (WGS84), in degrees * 1E7
+ * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
+ * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ * @param satellites_visible Number of satellites visible. If unknown, set to 255
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
+    _mav_put_uint64_t(buf, 0, time_usec);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_int32_t(buf, 16, alt);
+    _mav_put_uint16_t(buf, 20, eph);
+    _mav_put_uint16_t(buf, 22, epv);
+    _mav_put_uint16_t(buf, 24, vel);
+    _mav_put_uint16_t(buf, 26, cog);
+    _mav_put_uint8_t(buf, 28, fix_type);
+    _mav_put_uint8_t(buf, 29, satellites_visible);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#else
+    mavlink_gps_raw_int_t packet;
+    packet.time_usec = time_usec;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.alt = alt;
+    packet.eph = eph;
+    packet.epv = epv;
+    packet.vel = vel;
+    packet.cog = cog;
+    packet.fix_type = fix_type;
+    packet.satellites_visible = satellites_visible;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gps_raw_int message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, time_usec);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_int32_t(buf, 16, alt);
+    _mav_put_uint16_t(buf, 20, eph);
+    _mav_put_uint16_t(buf, 22, epv);
+    _mav_put_uint16_t(buf, 24, vel);
+    _mav_put_uint16_t(buf, 26, cog);
+    _mav_put_uint8_t(buf, 28, fix_type);
+    _mav_put_uint8_t(buf, 29, satellites_visible);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#else
+    mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf;
+    packet->time_usec = time_usec;
+    packet->lat = lat;
+    packet->lon = lon;
+    packet->alt = alt;
+    packet->eph = eph;
+    packet->epv = epv;
+    packet->vel = vel;
+    packet->cog = cog;
+    packet->fix_type = fix_type;
+    packet->satellites_visible = satellites_visible;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GPS_RAW_INT UNPACKING
+
+
+/**
+ * @brief Get field time_usec from gps_raw_int message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field fix_type from gps_raw_int message
+ *
+ * @return See the GPS_FIX_TYPE enum.
+ */
+static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  28);
+}
+
+/**
+ * @brief Get field lat from gps_raw_int message
+ *
+ * @return Latitude (WGS84), in degrees * 1E7
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  8);
+}
+
+/**
+ * @brief Get field lon from gps_raw_int message
+ *
+ * @return Longitude (WGS84), in degrees * 1E7
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  12);
+}
+
+/**
+ * @brief Get field alt from gps_raw_int message
+ *
+ * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  16);
+}
+
+/**
+ * @brief Get field eph from gps_raw_int message
+ *
+ * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  20);
+}
+
+/**
+ * @brief Get field epv from gps_raw_int message
+ *
+ * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  22);
+}
+
+/**
+ * @brief Get field vel from gps_raw_int message
+ *
+ * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  24);
+}
+
+/**
+ * @brief Get field cog from gps_raw_int message
+ *
+ * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  26);
+}
+
+/**
+ * @brief Get field satellites_visible from gps_raw_int message
+ *
+ * @return Number of satellites visible. If unknown, set to 255
+ */
+static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  29);
+}
+
+/**
+ * @brief Decode a gps_raw_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_raw_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg);
+    gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
+    gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
+    gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
+    gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
+    gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
+    gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg);
+    gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
+    gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
+    gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
+        memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+    memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_heartbeat.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,336 @@
+#pragma once
+// MESSAGE HEARTBEAT PACKING
+
+#define MAVLINK_MSG_ID_HEARTBEAT 0
+
+MAVPACKED(
+typedef struct __mavlink_heartbeat_t {
+ uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
+ uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/
+ uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/
+ uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h*/
+ uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/
+ uint8_t mavlink_version; /*< MAVLink version*/
+}) mavlink_heartbeat_t;
+
+#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
+#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9
+#define MAVLINK_MSG_ID_0_LEN 9
+#define MAVLINK_MSG_ID_0_MIN_LEN 9
+
+#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
+#define MAVLINK_MSG_ID_0_CRC 50
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
+    0, \
+    "HEARTBEAT", \
+    6, \
+    {  { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
+         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
+         { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
+         { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
+         { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
+         { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
+    "HEARTBEAT", \
+    6, \
+    {  { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
+         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
+         { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
+         { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
+         { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
+         { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
+ * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ * @param custom_mode A bitfield for use for autopilot-specific flags.
+ * @param system_status System status flag, see MAV_STATE ENUM
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
+    _mav_put_uint32_t(buf, 0, custom_mode);
+    _mav_put_uint8_t(buf, 4, type);
+    _mav_put_uint8_t(buf, 5, autopilot);
+    _mav_put_uint8_t(buf, 6, base_mode);
+    _mav_put_uint8_t(buf, 7, system_status);
+    _mav_put_uint8_t(buf, 8, 2);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#else
+    mavlink_heartbeat_t packet;
+    packet.custom_mode = custom_mode;
+    packet.type = type;
+    packet.autopilot = autopilot;
+    packet.base_mode = base_mode;
+    packet.system_status = system_status;
+    packet.mavlink_version = 2;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
+ * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ * @param custom_mode A bitfield for use for autopilot-specific flags.
+ * @param system_status System status flag, see MAV_STATE ENUM
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
+    _mav_put_uint32_t(buf, 0, custom_mode);
+    _mav_put_uint8_t(buf, 4, type);
+    _mav_put_uint8_t(buf, 5, autopilot);
+    _mav_put_uint8_t(buf, 6, base_mode);
+    _mav_put_uint8_t(buf, 7, system_status);
+    _mav_put_uint8_t(buf, 8, 2);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#else
+    mavlink_heartbeat_t packet;
+    packet.custom_mode = custom_mode;
+    packet.type = type;
+    packet.autopilot = autopilot;
+    packet.base_mode = base_mode;
+    packet.system_status = system_status;
+    packet.mavlink_version = 2;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
+{
+    return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
+}
+
+/**
+ * @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
+{
+    return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
+}
+
+/**
+ * @brief Send a heartbeat message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
+ * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ * @param custom_mode A bitfield for use for autopilot-specific flags.
+ * @param system_status System status flag, see MAV_STATE ENUM
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
+    _mav_put_uint32_t(buf, 0, custom_mode);
+    _mav_put_uint8_t(buf, 4, type);
+    _mav_put_uint8_t(buf, 5, autopilot);
+    _mav_put_uint8_t(buf, 6, base_mode);
+    _mav_put_uint8_t(buf, 7, system_status);
+    _mav_put_uint8_t(buf, 8, 2);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#else
+    mavlink_heartbeat_t packet;
+    packet.custom_mode = custom_mode;
+    packet.type = type;
+    packet.autopilot = autopilot;
+    packet.base_mode = base_mode;
+    packet.system_status = system_status;
+    packet.mavlink_version = 2;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a heartbeat message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, custom_mode);
+    _mav_put_uint8_t(buf, 4, type);
+    _mav_put_uint8_t(buf, 5, autopilot);
+    _mav_put_uint8_t(buf, 6, base_mode);
+    _mav_put_uint8_t(buf, 7, system_status);
+    _mav_put_uint8_t(buf, 8, 2);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#else
+    mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
+    packet->custom_mode = custom_mode;
+    packet->type = type;
+    packet->autopilot = autopilot;
+    packet->base_mode = base_mode;
+    packet->system_status = system_status;
+    packet->mavlink_version = 2;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE HEARTBEAT UNPACKING
+
+
+/**
+ * @brief Get field type from heartbeat message
+ *
+ * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  4);
+}
+
+/**
+ * @brief Get field autopilot from heartbeat message
+ *
+ * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  5);
+}
+
+/**
+ * @brief Get field base_mode from heartbeat message
+ *
+ * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  6);
+}
+
+/**
+ * @brief Get field custom_mode from heartbeat message
+ *
+ * @return A bitfield for use for autopilot-specific flags.
+ */
+static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field system_status from heartbeat message
+ *
+ * @return System status flag, see MAV_STATE ENUM
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  7);
+}
+
+/**
+ * @brief Get field mavlink_version from heartbeat message
+ *
+ * @return MAVLink version
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  8);
+}
+
+/**
+ * @brief Decode a heartbeat message into a struct
+ *
+ * @param msg The message to decode
+ * @param heartbeat C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
+    heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
+    heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
+    heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
+    heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
+    heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN;
+        memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+    memcpy(heartbeat, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_local_position_ned.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,364 @@
+#pragma once
+// MESSAGE LOCAL_POSITION_NED PACKING
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32
+
+MAVPACKED(
+typedef struct __mavlink_local_position_ned_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ float x; /*< X Position*/
+ float y; /*< Y Position*/
+ float z; /*< Z Position*/
+ float vx; /*< X Speed*/
+ float vy; /*< Y Speed*/
+ float vz; /*< Z Speed*/
+}) mavlink_local_position_ned_t;
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28
+#define MAVLINK_MSG_ID_32_LEN 28
+#define MAVLINK_MSG_ID_32_MIN_LEN 28
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185
+#define MAVLINK_MSG_ID_32_CRC 185
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \
+    32, \
+    "LOCAL_POSITION_NED", \
+    7, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \
+         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \
+         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \
+         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \
+         { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \
+         { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \
+         { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \
+    "LOCAL_POSITION_NED", \
+    7, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \
+         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \
+         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \
+         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \
+         { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \
+         { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \
+         { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a local_position_ned 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, x);
+    _mav_put_float(buf, 8, y);
+    _mav_put_float(buf, 12, z);
+    _mav_put_float(buf, 16, vx);
+    _mav_put_float(buf, 20, vy);
+    _mav_put_float(buf, 24, vz);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#else
+    mavlink_local_position_ned_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.x = x;
+    packet.y = y;
+    packet.z = z;
+    packet.vx = vx;
+    packet.vy = vy;
+    packet.vz = vz;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+}
+
+/**
+ * @brief Pack a local_position_ned 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, x);
+    _mav_put_float(buf, 8, y);
+    _mav_put_float(buf, 12, z);
+    _mav_put_float(buf, 16, vx);
+    _mav_put_float(buf, 20, vy);
+    _mav_put_float(buf, 24, vz);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#else
+    mavlink_local_position_ned_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.x = x;
+    packet.y = y;
+    packet.z = z;
+    packet.vx = vx;
+    packet.vy = vy;
+    packet.vz = vz;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+}
+
+/**
+ * @brief Encode a local_position_ned 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 local_position_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned)
+{
+    return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
+}
+
+/**
+ * @brief Encode a local_position_ned 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 local_position_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned)
+{
+    return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
+}
+
+/**
+ * @brief Send a local_position_ned message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, x);
+    _mav_put_float(buf, 8, y);
+    _mav_put_float(buf, 12, z);
+    _mav_put_float(buf, 16, vx);
+    _mav_put_float(buf, 20, vy);
+    _mav_put_float(buf, 24, vz);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#else
+    mavlink_local_position_ned_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.x = x;
+    packet.y = y;
+    packet.z = z;
+    packet.vx = vx;
+    packet.vy = vy;
+    packet.vz = vz;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#endif
+}
+
+/**
+ * @brief Send a local_position_ned message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_local_position_ned_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_t* local_position_ned)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_local_position_ned_send(chan, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)local_position_ned, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, x);
+    _mav_put_float(buf, 8, y);
+    _mav_put_float(buf, 12, z);
+    _mav_put_float(buf, 16, vx);
+    _mav_put_float(buf, 20, vy);
+    _mav_put_float(buf, 24, vz);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#else
+    mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->x = x;
+    packet->y = y;
+    packet->z = z;
+    packet->vx = vx;
+    packet->vy = vy;
+    packet->vz = vz;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE LOCAL_POSITION_NED UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from local_position_ned message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field x from local_position_ned message
+ *
+ * @return X Position
+ */
+static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Get field y from local_position_ned message
+ *
+ * @return Y Position
+ */
+static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field z from local_position_ned message
+ *
+ * @return Z Position
+ */
+static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field vx from local_position_ned message
+ *
+ * @return X Speed
+ */
+static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field vy from local_position_ned message
+ *
+ * @return Y Speed
+ */
+static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field vz from local_position_ned message
+ *
+ * @return Z Speed
+ */
+static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Decode a local_position_ned message into a struct
+ *
+ * @param msg The message to decode
+ * @param local_position_ned C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg);
+    local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg);
+    local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg);
+    local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg);
+    local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg);
+    local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg);
+    local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN;
+        memset(local_position_ned, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+    memcpy(local_position_ned, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_range_to_node.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,289 @@
+#pragma once
+// MESSAGE RANGE_TO_NODE PACKING
+
+#define MAVLINK_MSG_ID_RANGE_TO_NODE 150
+
+MAVPACKED(
+typedef struct __mavlink_range_to_node_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ float range; /*<  range between nodes in (meters)*/
+ uint8_t my_id; /*<  ID of the sending node */
+ uint8_t tgt_id; /*<  ID of the receiving node */
+}) mavlink_range_to_node_t;
+
+#define MAVLINK_MSG_ID_RANGE_TO_NODE_LEN 10
+#define MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN 10
+#define MAVLINK_MSG_ID_150_LEN 10
+#define MAVLINK_MSG_ID_150_MIN_LEN 10
+
+#define MAVLINK_MSG_ID_RANGE_TO_NODE_CRC 2
+#define MAVLINK_MSG_ID_150_CRC 2
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RANGE_TO_NODE { \
+    150, \
+    "RANGE_TO_NODE", \
+    4, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_range_to_node_t, time_boot_ms) }, \
+         { "range", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_range_to_node_t, range) }, \
+         { "my_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_range_to_node_t, my_id) }, \
+         { "tgt_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_range_to_node_t, tgt_id) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RANGE_TO_NODE { \
+    "RANGE_TO_NODE", \
+    4, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_range_to_node_t, time_boot_ms) }, \
+         { "range", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_range_to_node_t, range) }, \
+         { "my_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_range_to_node_t, my_id) }, \
+         { "tgt_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_range_to_node_t, tgt_id) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a range_to_node 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param my_id  ID of the sending node 
+ * @param tgt_id  ID of the receiving node 
+ * @param range  range between nodes in (meters)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_range_to_node_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, uint8_t my_id, uint8_t tgt_id, float range)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_RANGE_TO_NODE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, range);
+    _mav_put_uint8_t(buf, 8, my_id);
+    _mav_put_uint8_t(buf, 9, tgt_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN);
+#else
+    mavlink_range_to_node_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.range = range;
+    packet.my_id = my_id;
+    packet.tgt_id = tgt_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_RANGE_TO_NODE;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+}
+
+/**
+ * @brief Pack a range_to_node 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param my_id  ID of the sending node 
+ * @param tgt_id  ID of the receiving node 
+ * @param range  range between nodes in (meters)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_range_to_node_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,uint8_t my_id,uint8_t tgt_id,float range)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_RANGE_TO_NODE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, range);
+    _mav_put_uint8_t(buf, 8, my_id);
+    _mav_put_uint8_t(buf, 9, tgt_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN);
+#else
+    mavlink_range_to_node_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.range = range;
+    packet.my_id = my_id;
+    packet.tgt_id = tgt_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_RANGE_TO_NODE;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+}
+
+/**
+ * @brief Encode a range_to_node 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 range_to_node C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_range_to_node_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_range_to_node_t* range_to_node)
+{
+    return mavlink_msg_range_to_node_pack(system_id, component_id, msg, range_to_node->time_boot_ms, range_to_node->my_id, range_to_node->tgt_id, range_to_node->range);
+}
+
+/**
+ * @brief Encode a range_to_node 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 range_to_node C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_range_to_node_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_range_to_node_t* range_to_node)
+{
+    return mavlink_msg_range_to_node_pack_chan(system_id, component_id, chan, msg, range_to_node->time_boot_ms, range_to_node->my_id, range_to_node->tgt_id, range_to_node->range);
+}
+
+/**
+ * @brief Send a range_to_node message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param my_id  ID of the sending node 
+ * @param tgt_id  ID of the receiving node 
+ * @param range  range between nodes in (meters)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_range_to_node_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t my_id, uint8_t tgt_id, float range)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_RANGE_TO_NODE_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, range);
+    _mav_put_uint8_t(buf, 8, my_id);
+    _mav_put_uint8_t(buf, 9, tgt_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGE_TO_NODE, buf, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+#else
+    mavlink_range_to_node_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.range = range;
+    packet.my_id = my_id;
+    packet.tgt_id = tgt_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGE_TO_NODE, (const char *)&packet, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a range_to_node message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_range_to_node_send_struct(mavlink_channel_t chan, const mavlink_range_to_node_t* range_to_node)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_range_to_node_send(chan, range_to_node->time_boot_ms, range_to_node->my_id, range_to_node->tgt_id, range_to_node->range);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGE_TO_NODE, (const char *)range_to_node, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RANGE_TO_NODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_range_to_node_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t my_id, uint8_t tgt_id, float range)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_float(buf, 4, range);
+    _mav_put_uint8_t(buf, 8, my_id);
+    _mav_put_uint8_t(buf, 9, tgt_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGE_TO_NODE, buf, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+#else
+    mavlink_range_to_node_t *packet = (mavlink_range_to_node_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->range = range;
+    packet->my_id = my_id;
+    packet->tgt_id = tgt_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGE_TO_NODE, (const char *)packet, MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN, MAVLINK_MSG_ID_RANGE_TO_NODE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RANGE_TO_NODE UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from range_to_node message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_range_to_node_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field my_id from range_to_node message
+ *
+ * @return  ID of the sending node 
+ */
+static inline uint8_t mavlink_msg_range_to_node_get_my_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  8);
+}
+
+/**
+ * @brief Get field tgt_id from range_to_node message
+ *
+ * @return  ID of the receiving node 
+ */
+static inline uint8_t mavlink_msg_range_to_node_get_tgt_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  9);
+}
+
+/**
+ * @brief Get field range from range_to_node message
+ *
+ * @return  range between nodes in (meters)
+ */
+static inline float mavlink_msg_range_to_node_get_range(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Decode a range_to_node message into a struct
+ *
+ * @param msg The message to decode
+ * @param range_to_node C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_range_to_node_decode(const mavlink_message_t* msg, mavlink_range_to_node_t* range_to_node)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    range_to_node->time_boot_ms = mavlink_msg_range_to_node_get_time_boot_ms(msg);
+    range_to_node->range = mavlink_msg_range_to_node_get_range(msg);
+    range_to_node->my_id = mavlink_msg_range_to_node_get_my_id(msg);
+    range_to_node->tgt_id = mavlink_msg_range_to_node_get_tgt_id(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_RANGE_TO_NODE_LEN? msg->len : MAVLINK_MSG_ID_RANGE_TO_NODE_LEN;
+        memset(range_to_node, 0, MAVLINK_MSG_ID_RANGE_TO_NODE_LEN);
+    memcpy(range_to_node, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_scaled_imu.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,439 @@
+#pragma once
+// MESSAGE SCALED_IMU PACKING
+
+#define MAVLINK_MSG_ID_SCALED_IMU 26
+
+MAVPACKED(
+typedef struct __mavlink_scaled_imu_t {
+ uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
+ int16_t xacc; /*< X acceleration (mg)*/
+ int16_t yacc; /*< Y acceleration (mg)*/
+ int16_t zacc; /*< Z acceleration (mg)*/
+ int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/
+ int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/
+ int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/
+ int16_t xmag; /*< X Magnetic field (milli tesla)*/
+ int16_t ymag; /*< Y Magnetic field (milli tesla)*/
+ int16_t zmag; /*< Z Magnetic field (milli tesla)*/
+}) mavlink_scaled_imu_t;
+
+#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22
+#define MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN 22
+#define MAVLINK_MSG_ID_26_LEN 22
+#define MAVLINK_MSG_ID_26_MIN_LEN 22
+
+#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170
+#define MAVLINK_MSG_ID_26_CRC 170
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
+    26, \
+    "SCALED_IMU", \
+    10, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \
+         { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \
+         { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \
+         { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \
+         { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \
+         { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \
+         { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \
+         { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \
+         { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \
+         { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
+    "SCALED_IMU", \
+    10, \
+    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \
+         { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \
+         { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \
+         { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \
+         { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \
+         { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \
+         { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \
+         { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \
+         { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \
+         { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a scaled_imu 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @param xgyro Angular speed around X axis (millirad /sec)
+ * @param ygyro Angular speed around Y axis (millirad /sec)
+ * @param zgyro Angular speed around Z axis (millirad /sec)
+ * @param xmag X Magnetic field (milli tesla)
+ * @param ymag Y Magnetic field (milli tesla)
+ * @param zmag Z Magnetic field (milli tesla)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_int16_t(buf, 4, xacc);
+    _mav_put_int16_t(buf, 6, yacc);
+    _mav_put_int16_t(buf, 8, zacc);
+    _mav_put_int16_t(buf, 10, xgyro);
+    _mav_put_int16_t(buf, 12, ygyro);
+    _mav_put_int16_t(buf, 14, zgyro);
+    _mav_put_int16_t(buf, 16, xmag);
+    _mav_put_int16_t(buf, 18, ymag);
+    _mav_put_int16_t(buf, 20, zmag);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#else
+    mavlink_scaled_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.xacc = xacc;
+    packet.yacc = yacc;
+    packet.zacc = zacc;
+    packet.xgyro = xgyro;
+    packet.ygyro = ygyro;
+    packet.zgyro = zgyro;
+    packet.xmag = xmag;
+    packet.ymag = ymag;
+    packet.zmag = zmag;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+}
+
+/**
+ * @brief Pack a scaled_imu 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 time_boot_ms Timestamp (milliseconds since system boot)
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @param xgyro Angular speed around X axis (millirad /sec)
+ * @param ygyro Angular speed around Y axis (millirad /sec)
+ * @param zgyro Angular speed around Z axis (millirad /sec)
+ * @param xmag X Magnetic field (milli tesla)
+ * @param ymag Y Magnetic field (milli tesla)
+ * @param zmag Z Magnetic field (milli tesla)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_int16_t(buf, 4, xacc);
+    _mav_put_int16_t(buf, 6, yacc);
+    _mav_put_int16_t(buf, 8, zacc);
+    _mav_put_int16_t(buf, 10, xgyro);
+    _mav_put_int16_t(buf, 12, ygyro);
+    _mav_put_int16_t(buf, 14, zgyro);
+    _mav_put_int16_t(buf, 16, xmag);
+    _mav_put_int16_t(buf, 18, ymag);
+    _mav_put_int16_t(buf, 20, zmag);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#else
+    mavlink_scaled_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.xacc = xacc;
+    packet.yacc = yacc;
+    packet.zacc = zacc;
+    packet.xgyro = xgyro;
+    packet.ygyro = ygyro;
+    packet.zgyro = zgyro;
+    packet.xmag = xmag;
+    packet.ymag = ymag;
+    packet.zmag = zmag;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+}
+
+/**
+ * @brief Encode a scaled_imu 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 scaled_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
+{
+    return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
+}
+
+/**
+ * @brief Encode a scaled_imu 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 scaled_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
+{
+    return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
+}
+
+/**
+ * @brief Send a scaled_imu message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @param xgyro Angular speed around X axis (millirad /sec)
+ * @param ygyro Angular speed around Y axis (millirad /sec)
+ * @param zgyro Angular speed around Z axis (millirad /sec)
+ * @param xmag X Magnetic field (milli tesla)
+ * @param ymag Y Magnetic field (milli tesla)
+ * @param zmag Z Magnetic field (milli tesla)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_int16_t(buf, 4, xacc);
+    _mav_put_int16_t(buf, 6, yacc);
+    _mav_put_int16_t(buf, 8, zacc);
+    _mav_put_int16_t(buf, 10, xgyro);
+    _mav_put_int16_t(buf, 12, ygyro);
+    _mav_put_int16_t(buf, 14, zgyro);
+    _mav_put_int16_t(buf, 16, xmag);
+    _mav_put_int16_t(buf, 18, ymag);
+    _mav_put_int16_t(buf, 20, zmag);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#else
+    mavlink_scaled_imu_t packet;
+    packet.time_boot_ms = time_boot_ms;
+    packet.xacc = xacc;
+    packet.yacc = yacc;
+    packet.zacc = zacc;
+    packet.xgyro = xgyro;
+    packet.ygyro = ygyro;
+    packet.zgyro = zgyro;
+    packet.xmag = xmag;
+    packet.ymag = ymag;
+    packet.zmag = zmag;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#endif
+}
+
+/**
+ * @brief Send a scaled_imu message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_scaled_imu_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu_t* scaled_imu)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_scaled_imu_send(chan, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)scaled_imu, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, time_boot_ms);
+    _mav_put_int16_t(buf, 4, xacc);
+    _mav_put_int16_t(buf, 6, yacc);
+    _mav_put_int16_t(buf, 8, zacc);
+    _mav_put_int16_t(buf, 10, xgyro);
+    _mav_put_int16_t(buf, 12, ygyro);
+    _mav_put_int16_t(buf, 14, zgyro);
+    _mav_put_int16_t(buf, 16, xmag);
+    _mav_put_int16_t(buf, 18, ymag);
+    _mav_put_int16_t(buf, 20, zmag);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#else
+    mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf;
+    packet->time_boot_ms = time_boot_ms;
+    packet->xacc = xacc;
+    packet->yacc = yacc;
+    packet->zacc = zacc;
+    packet->xgyro = xgyro;
+    packet->ygyro = ygyro;
+    packet->zgyro = zgyro;
+    packet->xmag = xmag;
+    packet->ymag = ymag;
+    packet->zmag = zmag;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SCALED_IMU UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from scaled_imu message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field xacc from scaled_imu message
+ *
+ * @return X acceleration (mg)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  4);
+}
+
+/**
+ * @brief Get field yacc from scaled_imu message
+ *
+ * @return Y acceleration (mg)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  6);
+}
+
+/**
+ * @brief Get field zacc from scaled_imu message
+ *
+ * @return Z acceleration (mg)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  8);
+}
+
+/**
+ * @brief Get field xgyro from scaled_imu message
+ *
+ * @return Angular speed around X axis (millirad /sec)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  10);
+}
+
+/**
+ * @brief Get field ygyro from scaled_imu message
+ *
+ * @return Angular speed around Y axis (millirad /sec)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  12);
+}
+
+/**
+ * @brief Get field zgyro from scaled_imu message
+ *
+ * @return Angular speed around Z axis (millirad /sec)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  14);
+}
+
+/**
+ * @brief Get field xmag from scaled_imu message
+ *
+ * @return X Magnetic field (milli tesla)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  16);
+}
+
+/**
+ * @brief Get field ymag from scaled_imu message
+ *
+ * @return Y Magnetic field (milli tesla)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  18);
+}
+
+/**
+ * @brief Get field zmag from scaled_imu message
+ *
+ * @return Z Magnetic field (milli tesla)
+ */
+static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  20);
+}
+
+/**
+ * @brief Decode a scaled_imu message into a struct
+ *
+ * @param msg The message to decode
+ * @param scaled_imu C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg);
+    scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg);
+    scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg);
+    scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg);
+    scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
+    scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
+    scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
+    scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg);
+    scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg);
+    scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU_LEN;
+        memset(scaled_imu, 0, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+    memcpy(scaled_imu, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_sys_status.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,514 @@
+#pragma once
+// MESSAGE SYS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_SYS_STATUS 1
+
+MAVPACKED(
+typedef struct __mavlink_sys_status_t {
+ uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/
+ uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/
+ uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/
+ uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/
+ uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/
+ int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/
+ uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/
+ uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/
+ uint16_t errors_count1; /*< Autopilot-specific errors*/
+ uint16_t errors_count2; /*< Autopilot-specific errors*/
+ uint16_t errors_count3; /*< Autopilot-specific errors*/
+ uint16_t errors_count4; /*< Autopilot-specific errors*/
+ int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/
+}) mavlink_sys_status_t;
+
+#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31
+#define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31
+#define MAVLINK_MSG_ID_1_LEN 31
+#define MAVLINK_MSG_ID_1_MIN_LEN 31
+
+#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124
+#define MAVLINK_MSG_ID_1_CRC 124
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
+    1, \
+    "SYS_STATUS", \
+    13, \
+    {  { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
+         { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
+         { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
+         { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
+         { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
+         { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
+         { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
+         { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
+         { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
+         { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
+         { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
+         { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
+         { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
+    "SYS_STATUS", \
+    13, \
+    {  { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
+         { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
+         { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
+         { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
+         { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
+         { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
+         { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
+         { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
+         { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
+         { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
+         { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
+         { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
+         { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a sys_status 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 onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_count1 Autopilot-specific errors
+ * @param errors_count2 Autopilot-specific errors
+ * @param errors_count3 Autopilot-specific errors
+ * @param errors_count4 Autopilot-specific errors
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
+    _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
+    _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
+    _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
+    _mav_put_uint16_t(buf, 12, load);
+    _mav_put_uint16_t(buf, 14, voltage_battery);
+    _mav_put_int16_t(buf, 16, current_battery);
+    _mav_put_uint16_t(buf, 18, drop_rate_comm);
+    _mav_put_uint16_t(buf, 20, errors_comm);
+    _mav_put_uint16_t(buf, 22, errors_count1);
+    _mav_put_uint16_t(buf, 24, errors_count2);
+    _mav_put_uint16_t(buf, 26, errors_count3);
+    _mav_put_uint16_t(buf, 28, errors_count4);
+    _mav_put_int8_t(buf, 30, battery_remaining);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#else
+    mavlink_sys_status_t packet;
+    packet.onboard_control_sensors_present = onboard_control_sensors_present;
+    packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
+    packet.onboard_control_sensors_health = onboard_control_sensors_health;
+    packet.load = load;
+    packet.voltage_battery = voltage_battery;
+    packet.current_battery = current_battery;
+    packet.drop_rate_comm = drop_rate_comm;
+    packet.errors_comm = errors_comm;
+    packet.errors_count1 = errors_count1;
+    packet.errors_count2 = errors_count2;
+    packet.errors_count3 = errors_count3;
+    packet.errors_count4 = errors_count4;
+    packet.battery_remaining = battery_remaining;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a sys_status 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 onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_count1 Autopilot-specific errors
+ * @param errors_count2 Autopilot-specific errors
+ * @param errors_count3 Autopilot-specific errors
+ * @param errors_count4 Autopilot-specific errors
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
+    _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
+    _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
+    _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
+    _mav_put_uint16_t(buf, 12, load);
+    _mav_put_uint16_t(buf, 14, voltage_battery);
+    _mav_put_int16_t(buf, 16, current_battery);
+    _mav_put_uint16_t(buf, 18, drop_rate_comm);
+    _mav_put_uint16_t(buf, 20, errors_comm);
+    _mav_put_uint16_t(buf, 22, errors_count1);
+    _mav_put_uint16_t(buf, 24, errors_count2);
+    _mav_put_uint16_t(buf, 26, errors_count3);
+    _mav_put_uint16_t(buf, 28, errors_count4);
+    _mav_put_int8_t(buf, 30, battery_remaining);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#else
+    mavlink_sys_status_t packet;
+    packet.onboard_control_sensors_present = onboard_control_sensors_present;
+    packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
+    packet.onboard_control_sensors_health = onboard_control_sensors_health;
+    packet.load = load;
+    packet.voltage_battery = voltage_battery;
+    packet.current_battery = current_battery;
+    packet.drop_rate_comm = drop_rate_comm;
+    packet.errors_comm = errors_comm;
+    packet.errors_count1 = errors_count1;
+    packet.errors_count2 = errors_count2;
+    packet.errors_count3 = errors_count3;
+    packet.errors_count4 = errors_count4;
+    packet.battery_remaining = battery_remaining;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a sys_status 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 sys_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
+{
+    return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
+}
+
+/**
+ * @brief Encode a sys_status 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 sys_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
+{
+    return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
+}
+
+/**
+ * @brief Send a sys_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ * @param errors_count1 Autopilot-specific errors
+ * @param errors_count2 Autopilot-specific errors
+ * @param errors_count3 Autopilot-specific errors
+ * @param errors_count4 Autopilot-specific errors
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
+    _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
+    _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
+    _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
+    _mav_put_uint16_t(buf, 12, load);
+    _mav_put_uint16_t(buf, 14, voltage_battery);
+    _mav_put_int16_t(buf, 16, current_battery);
+    _mav_put_uint16_t(buf, 18, drop_rate_comm);
+    _mav_put_uint16_t(buf, 20, errors_comm);
+    _mav_put_uint16_t(buf, 22, errors_count1);
+    _mav_put_uint16_t(buf, 24, errors_count2);
+    _mav_put_uint16_t(buf, 26, errors_count3);
+    _mav_put_uint16_t(buf, 28, errors_count4);
+    _mav_put_int8_t(buf, 30, battery_remaining);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#else
+    mavlink_sys_status_t packet;
+    packet.onboard_control_sensors_present = onboard_control_sensors_present;
+    packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
+    packet.onboard_control_sensors_health = onboard_control_sensors_health;
+    packet.load = load;
+    packet.voltage_battery = voltage_battery;
+    packet.current_battery = current_battery;
+    packet.drop_rate_comm = drop_rate_comm;
+    packet.errors_comm = errors_comm;
+    packet.errors_count1 = errors_count1;
+    packet.errors_count2 = errors_count2;
+    packet.errors_count3 = errors_count3;
+    packet.errors_count4 = errors_count4;
+    packet.battery_remaining = battery_remaining;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a sys_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_sys_status_send_struct(mavlink_channel_t chan, const mavlink_sys_status_t* sys_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_sys_status_send(chan, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)sys_status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
+    _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
+    _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
+    _mav_put_uint16_t(buf, 12, load);
+    _mav_put_uint16_t(buf, 14, voltage_battery);
+    _mav_put_int16_t(buf, 16, current_battery);
+    _mav_put_uint16_t(buf, 18, drop_rate_comm);
+    _mav_put_uint16_t(buf, 20, errors_comm);
+    _mav_put_uint16_t(buf, 22, errors_count1);
+    _mav_put_uint16_t(buf, 24, errors_count2);
+    _mav_put_uint16_t(buf, 26, errors_count3);
+    _mav_put_uint16_t(buf, 28, errors_count4);
+    _mav_put_int8_t(buf, 30, battery_remaining);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#else
+    mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf;
+    packet->onboard_control_sensors_present = onboard_control_sensors_present;
+    packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled;
+    packet->onboard_control_sensors_health = onboard_control_sensors_health;
+    packet->load = load;
+    packet->voltage_battery = voltage_battery;
+    packet->current_battery = current_battery;
+    packet->drop_rate_comm = drop_rate_comm;
+    packet->errors_comm = errors_comm;
+    packet->errors_count1 = errors_count1;
+    packet->errors_count2 = errors_count2;
+    packet->errors_count3 = errors_count3;
+    packet->errors_count4 = errors_count4;
+    packet->battery_remaining = battery_remaining;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SYS_STATUS UNPACKING
+
+
+/**
+ * @brief Get field onboard_control_sensors_present from sys_status message
+ *
+ * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ */
+static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field onboard_control_sensors_enabled from sys_status message
+ *
+ * @return Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ */
+static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  4);
+}
+
+/**
+ * @brief Get field onboard_control_sensors_health from sys_status message
+ *
+ * @return Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
+ */
+static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
+}
+
+/**
+ * @brief Get field load from sys_status message
+ *
+ * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ */
+static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  12);
+}
+
+/**
+ * @brief Get field voltage_battery from sys_status message
+ *
+ * @return Battery voltage, in millivolts (1 = 1 millivolt)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  14);
+}
+
+/**
+ * @brief Get field current_battery from sys_status message
+ *
+ * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ */
+static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  16);
+}
+
+/**
+ * @brief Get field battery_remaining from sys_status message
+ *
+ * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ */
+static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int8_t(msg,  30);
+}
+
+/**
+ * @brief Get field drop_rate_comm from sys_status message
+ *
+ * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  18);
+}
+
+/**
+ * @brief Get field errors_comm from sys_status message
+ *
+ * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  20);
+}
+
+/**
+ * @brief Get field errors_count1 from sys_status message
+ *
+ * @return Autopilot-specific errors
+ */
+static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  22);
+}
+
+/**
+ * @brief Get field errors_count2 from sys_status message
+ *
+ * @return Autopilot-specific errors
+ */
+static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  24);
+}
+
+/**
+ * @brief Get field errors_count3 from sys_status message
+ *
+ * @return Autopilot-specific errors
+ */
+static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  26);
+}
+
+/**
+ * @brief Get field errors_count4 from sys_status message
+ *
+ * @return Autopilot-specific errors
+ */
+static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  28);
+}
+
+/**
+ * @brief Decode a sys_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param sys_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg);
+    sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg);
+    sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg);
+    sys_status->load = mavlink_msg_sys_status_get_load(msg);
+    sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg);
+    sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg);
+    sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
+    sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg);
+    sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg);
+    sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg);
+    sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg);
+    sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg);
+    sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_SYS_STATUS_LEN;
+        memset(sys_status, 0, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+    memcpy(sys_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/mavlink_msg_system_time.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,239 @@
+#pragma once
+// MESSAGE SYSTEM_TIME PACKING
+
+#define MAVLINK_MSG_ID_SYSTEM_TIME 2
+
+MAVPACKED(
+typedef struct __mavlink_system_time_t {
+ uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/
+ uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/
+}) mavlink_system_time_t;
+
+#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12
+#define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12
+#define MAVLINK_MSG_ID_2_LEN 12
+#define MAVLINK_MSG_ID_2_MIN_LEN 12
+
+#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
+#define MAVLINK_MSG_ID_2_CRC 137
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
+    2, \
+    "SYSTEM_TIME", \
+    2, \
+    {  { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
+         { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
+    "SYSTEM_TIME", \
+    2, \
+    {  { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
+         { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a system_time 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 time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t time_unix_usec, uint32_t time_boot_ms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
+    _mav_put_uint64_t(buf, 0, time_unix_usec);
+    _mav_put_uint32_t(buf, 8, time_boot_ms);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#else
+    mavlink_system_time_t packet;
+    packet.time_unix_usec = time_unix_usec;
+    packet.time_boot_ms = time_boot_ms;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+}
+
+/**
+ * @brief Pack a system_time 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 time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t time_unix_usec,uint32_t time_boot_ms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
+    _mav_put_uint64_t(buf, 0, time_unix_usec);
+    _mav_put_uint32_t(buf, 8, time_boot_ms);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#else
+    mavlink_system_time_t packet;
+    packet.time_unix_usec = time_unix_usec;
+    packet.time_boot_ms = time_boot_ms;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+}
+
+/**
+ * @brief Encode a system_time 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 system_time C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
+{
+    return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms);
+}
+
+/**
+ * @brief Encode a system_time 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 system_time C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
+{
+    return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms);
+}
+
+/**
+ * @brief Send a system_time message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
+    _mav_put_uint64_t(buf, 0, time_unix_usec);
+    _mav_put_uint32_t(buf, 8, time_boot_ms);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#else
+    mavlink_system_time_t packet;
+    packet.time_unix_usec = time_unix_usec;
+    packet.time_boot_ms = time_boot_ms;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#endif
+}
+
+/**
+ * @brief Send a system_time message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_system_time_send_struct(mavlink_channel_t chan, const mavlink_system_time_t* system_time)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_system_time_send(chan, system_time->time_unix_usec, system_time->time_boot_ms);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)system_time, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This varient of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_unix_usec, uint32_t time_boot_ms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, time_unix_usec);
+    _mav_put_uint32_t(buf, 8, time_boot_ms);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#else
+    mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf;
+    packet->time_unix_usec = time_unix_usec;
+    packet->time_boot_ms = time_boot_ms;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SYSTEM_TIME UNPACKING
+
+
+/**
+ * @brief Get field time_unix_usec from system_time message
+ *
+ * @return Timestamp of the master clock in microseconds since UNIX epoch.
+ */
+static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field time_boot_ms from system_time message
+ *
+ * @return Timestamp of the component clock since boot time in milliseconds.
+ */
+static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
+}
+
+/**
+ * @brief Decode a system_time message into a struct
+ *
+ * @param msg The message to decode
+ * @param system_time C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg);
+    system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TIME_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TIME_LEN;
+        memset(system_time, 0, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+    memcpy(system_time, _MAV_PAYLOAD(msg), len);
+#endif
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/testsuite.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,653 @@
+/** @file
+ *    @brief MAVLink comm protocol testsuite generated from emaxx_board.xml
+ *    @see http://qgroundcontrol.org/mavlink/
+ */
+#pragma once
+#ifndef EMAXX_BOARD_TESTSUITE_H
+#define EMAXX_BOARD_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+
+static void mavlink_test_emaxx_board(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_emaxx_board(system_id, component_id, last_msg);
+}
+#endif
+
+
+
+
+static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HEARTBEAT >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_heartbeat_t packet_in = {
+        963497464,17,84,151,218,2
+    };
+    mavlink_heartbeat_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.custom_mode = packet_in.custom_mode;
+        packet1.type = packet_in.type;
+        packet1.autopilot = packet_in.autopilot;
+        packet1.base_mode = packet_in.base_mode;
+        packet1.system_status = packet_in.system_status;
+        packet1.mavlink_version = packet_in.mavlink_version;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_heartbeat_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
+    mavlink_msg_heartbeat_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
+    mavlink_msg_heartbeat_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_heartbeat_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_heartbeat_send(MAVLINK_COMM_1 , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
+    mavlink_msg_heartbeat_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYS_STATUS >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_sys_status_t packet_in = {
+        963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,18587,18691,223
+    };
+    mavlink_sys_status_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present;
+        packet1.onboard_control_sensors_enabled = packet_in.onboard_control_sensors_enabled;
+        packet1.onboard_control_sensors_health = packet_in.onboard_control_sensors_health;
+        packet1.load = packet_in.load;
+        packet1.voltage_battery = packet_in.voltage_battery;
+        packet1.current_battery = packet_in.current_battery;
+        packet1.drop_rate_comm = packet_in.drop_rate_comm;
+        packet1.errors_comm = packet_in.errors_comm;
+        packet1.errors_count1 = packet_in.errors_count1;
+        packet1.errors_count2 = packet_in.errors_count2;
+        packet1.errors_count3 = packet_in.errors_count3;
+        packet1.errors_count4 = packet_in.errors_count4;
+        packet1.battery_remaining = packet_in.battery_remaining;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_sys_status_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
+    mavlink_msg_sys_status_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
+    mavlink_msg_sys_status_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_sys_status_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_sys_status_send(MAVLINK_COMM_1 , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
+    mavlink_msg_sys_status_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_system_time(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYSTEM_TIME >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_system_time_t packet_in = {
+        93372036854775807ULL,963497880
+    };
+    mavlink_system_time_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_unix_usec = packet_in.time_unix_usec;
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_system_time_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_unix_usec , packet1.time_boot_ms );
+    mavlink_msg_system_time_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_unix_usec , packet1.time_boot_ms );
+    mavlink_msg_system_time_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_system_time_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_system_time_send(MAVLINK_COMM_1 , packet1.time_unix_usec , packet1.time_boot_ms );
+    mavlink_msg_system_time_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RAW_INT >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_gps_raw_int_t packet_in = {
+        93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156
+    };
+    mavlink_gps_raw_int_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_usec = packet_in.time_usec;
+        packet1.lat = packet_in.lat;
+        packet1.lon = packet_in.lon;
+        packet1.alt = packet_in.alt;
+        packet1.eph = packet_in.eph;
+        packet1.epv = packet_in.epv;
+        packet1.vel = packet_in.vel;
+        packet1.cog = packet_in.cog;
+        packet1.fix_type = packet_in.fix_type;
+        packet1.satellites_visible = packet_in.satellites_visible;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_gps_raw_int_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
+    mavlink_msg_gps_raw_int_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
+    mavlink_msg_gps_raw_int_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_gps_raw_int_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gps_raw_int_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
+    mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_scaled_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_scaled_imu_t packet_in = {
+        963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275
+    };
+    mavlink_scaled_imu_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.xacc = packet_in.xacc;
+        packet1.yacc = packet_in.yacc;
+        packet1.zacc = packet_in.zacc;
+        packet1.xgyro = packet_in.xgyro;
+        packet1.ygyro = packet_in.ygyro;
+        packet1.zgyro = packet_in.zgyro;
+        packet1.xmag = packet_in.xmag;
+        packet1.ymag = packet_in.ymag;
+        packet1.zmag = packet_in.zmag;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_scaled_imu_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
+    mavlink_msg_scaled_imu_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
+    mavlink_msg_scaled_imu_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_scaled_imu_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_scaled_imu_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
+    mavlink_msg_scaled_imu_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_attitude(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_attitude_t packet_in = {
+        963497464,45.0,73.0,101.0,129.0,157.0,185.0
+    };
+    mavlink_attitude_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.roll = packet_in.roll;
+        packet1.pitch = packet_in.pitch;
+        packet1.yaw = packet_in.yaw;
+        packet1.rollspeed = packet_in.rollspeed;
+        packet1.pitchspeed = packet_in.pitchspeed;
+        packet1.yawspeed = packet_in.yawspeed;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_attitude_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_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_attitude_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_attitude_quaternion(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_attitude_quaternion_t packet_in = {
+        963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0
+    };
+    mavlink_attitude_quaternion_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.q1 = packet_in.q1;
+        packet1.q2 = packet_in.q2;
+        packet1.q3 = packet_in.q3;
+        packet1.q4 = packet_in.q4;
+        packet1.rollspeed = packet_in.rollspeed;
+        packet1.pitchspeed = packet_in.pitchspeed;
+        packet1.yawspeed = packet_in.yawspeed;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_quaternion_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_attitude_quaternion_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_quaternion_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_quaternion_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_quaternion_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_attitude_quaternion_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
+    mavlink_msg_attitude_quaternion_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_local_position_ned(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_local_position_ned_t packet_in = {
+        963497464,45.0,73.0,101.0,129.0,157.0,185.0
+    };
+    mavlink_local_position_ned_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.x = packet_in.x;
+        packet1.y = packet_in.y;
+        packet1.z = packet_in.z;
+        packet1.vx = packet_in.vx;
+        packet1.vy = packet_in.vy;
+        packet1.vz = packet_in.vz;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_local_position_ned_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_local_position_ned_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_local_position_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
+    mavlink_msg_local_position_ned_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_local_position_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
+    mavlink_msg_local_position_ned_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_local_position_ned_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_local_position_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
+    mavlink_msg_local_position_ned_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_range_to_node(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RANGE_TO_NODE >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_range_to_node_t packet_in = {
+        963497464,45.0,29,96
+    };
+    mavlink_range_to_node_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.range = packet_in.range;
+        packet1.my_id = packet_in.my_id;
+        packet1.tgt_id = packet_in.tgt_id;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RANGE_TO_NODE_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_range_to_node_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_range_to_node_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_range_to_node_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.my_id , packet1.tgt_id , packet1.range );
+    mavlink_msg_range_to_node_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_range_to_node_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.my_id , packet1.tgt_id , packet1.range );
+    mavlink_msg_range_to_node_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_range_to_node_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_range_to_node_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.my_id , packet1.tgt_id , packet1.range );
+    mavlink_msg_range_to_node_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_fused_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FUSED_IMU >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_fused_imu_t packet_in = {
+        963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0
+    };
+    mavlink_fused_imu_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.accel_x = packet_in.accel_x;
+        packet1.accel_y = packet_in.accel_y;
+        packet1.accel_z = packet_in.accel_z;
+        packet1.gyro_x = packet_in.gyro_x;
+        packet1.gyro_y = packet_in.gyro_y;
+        packet1.gyro_z = packet_in.gyro_z;
+        packet1.roll = packet_in.roll;
+        packet1.pitch = packet_in.pitch;
+        packet1.yaw = packet_in.yaw;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FUSED_IMU_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_fused_imu_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_fused_imu_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_fused_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.accel_x , packet1.accel_y , packet1.accel_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.roll , packet1.pitch , packet1.yaw );
+    mavlink_msg_fused_imu_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_fused_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.accel_x , packet1.accel_y , packet1.accel_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.roll , packet1.pitch , packet1.yaw );
+    mavlink_msg_fused_imu_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_fused_imu_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_fused_imu_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.accel_x , packet1.accel_y , packet1.accel_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.roll , packet1.pitch , packet1.yaw );
+    mavlink_msg_fused_imu_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_emaxx_board(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+    mavlink_test_heartbeat(system_id, component_id, last_msg);
+    mavlink_test_sys_status(system_id, component_id, last_msg);
+    mavlink_test_system_time(system_id, component_id, last_msg);
+    mavlink_test_gps_raw_int(system_id, component_id, last_msg);
+    mavlink_test_scaled_imu(system_id, component_id, last_msg);
+    mavlink_test_attitude(system_id, component_id, last_msg);
+    mavlink_test_attitude_quaternion(system_id, component_id, last_msg);
+    mavlink_test_local_position_ned(system_id, component_id, last_msg);
+    mavlink_test_range_to_node(system_id, component_id, last_msg);
+    mavlink_test_fused_imu(system_id, component_id, last_msg);
+}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // EMAXX_BOARD_TESTSUITE_H
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/emaxx_board/version.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,15 @@
+/** @file
+ *  @brief MAVLink comm protocol built from emaxx_board.xml
+ *  @see http://mavlink.org
+ */
+#pragma once
+ 
+#ifndef MAVLINK_VERSION_H
+#define MAVLINK_VERSION_H
+
+#define MAVLINK_BUILD_DATE "Fri Jan 20 2017"
+#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 40
+ 
+#endif // MAVLINK_VERSION_H
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mavlink_conversions.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,212 @@
+#ifndef  _MAVLINK_CONVERSIONS_H_
+#define  _MAVLINK_CONVERSIONS_H_
+
+/* enable math defines on Windows */
+#ifdef _MSC_VER
+#ifndef _USE_MATH_DEFINES
+#define _USE_MATH_DEFINES
+#endif
+#endif
+#include <math.h>
+
+#ifndef M_PI_2
+    #define M_PI_2 ((float)asin(1))
+#endif
+
+/**
+ * @file mavlink_conversions.h
+ *
+ * These conversion functions follow the NASA rotation standards definition file
+ * available online.
+ *
+ * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free
+ * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)
+ * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the
+ * protocol as widely as possible.
+ *
+ * @author James Goppert
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+
+/**
+ * Converts a quaternion to a rotation matrix
+ *
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ * @param dcm a 3x3 rotation matrix
+ */
+MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
+{
+    double a = quaternion[0];
+    double b = quaternion[1];
+    double c = quaternion[2];
+    double d = quaternion[3];
+    double aSq = a * a;
+    double bSq = b * b;
+    double cSq = c * c;
+    double dSq = d * d;
+    dcm[0][0] = aSq + bSq - cSq - dSq;
+    dcm[0][1] = 2 * (b * c - a * d);
+    dcm[0][2] = 2 * (a * c + b * d);
+    dcm[1][0] = 2 * (b * c + a * d);
+    dcm[1][1] = aSq - bSq + cSq - dSq;
+    dcm[1][2] = 2 * (c * d - a * b);
+    dcm[2][0] = 2 * (b * d - a * c);
+    dcm[2][1] = 2 * (a * b + c * d);
+    dcm[2][2] = aSq - bSq - cSq + dSq;
+}
+
+
+/**
+ * Converts a rotation matrix to euler angles
+ *
+ * @param dcm a 3x3 rotation matrix
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ */
+MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
+{
+    float phi, theta, psi;
+    theta = asin(-dcm[2][0]);
+
+    if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
+        phi = 0.0f;
+        psi = (atan2f(dcm[1][2] - dcm[0][1],
+                dcm[0][2] + dcm[1][1]) + phi);
+
+    } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
+        phi = 0.0f;
+        psi = atan2f(dcm[1][2] - dcm[0][1],
+                  dcm[0][2] + dcm[1][1] - phi);
+
+    } else {
+        phi = atan2f(dcm[2][1], dcm[2][2]);
+        psi = atan2f(dcm[1][0], dcm[0][0]);
+    }
+
+    *roll = phi;
+    *pitch = theta;
+    *yaw = psi;
+}
+
+
+/**
+ * Converts a quaternion to euler angles
+ *
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ */
+MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
+{
+    float dcm[3][3];
+    mavlink_quaternion_to_dcm(quaternion, dcm);
+    mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
+}
+
+
+/**
+ * Converts euler angles to a quaternion
+ *
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ */
+MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
+{
+    float cosPhi_2 = cosf(roll / 2);
+    float sinPhi_2 = sinf(roll / 2);
+    float cosTheta_2 = cosf(pitch / 2);
+    float sinTheta_2 = sinf(pitch / 2);
+    float cosPsi_2 = cosf(yaw / 2);
+    float sinPsi_2 = sinf(yaw / 2);
+    quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
+            sinPhi_2 * sinTheta_2 * sinPsi_2);
+    quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
+            cosPhi_2 * sinTheta_2 * sinPsi_2);
+    quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
+            sinPhi_2 * cosTheta_2 * sinPsi_2);
+    quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
+            sinPhi_2 * sinTheta_2 * cosPsi_2);
+}
+
+
+/**
+ * Converts a rotation matrix to a quaternion
+ * Reference:
+ *  - Shoemake, Quaternions,
+ *  http://www.cs.ucr.edu/~vbz/resources/quatut.pdf
+ *
+ * @param dcm a 3x3 rotation matrix
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ */
+MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
+{
+    float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
+    if (tr > 0.0f) {
+        float s = sqrtf(tr + 1.0f);
+        quaternion[0] = s * 0.5f;
+        s = 0.5f / s;
+        quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
+        quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
+        quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
+    } else {
+        /* Find maximum diagonal element in dcm
+         * store index in dcm_i */
+        int dcm_i = 0;
+        int i;
+        for (i = 1; i < 3; i++) {
+            if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
+                dcm_i = i;
+            }
+        }
+
+        int dcm_j = (dcm_i + 1) % 3;
+        int dcm_k = (dcm_i + 2) % 3;
+
+        float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
+                    dcm[dcm_k][dcm_k]) + 1.0f);
+        quaternion[dcm_i + 1] = s * 0.5f;
+        s = 0.5f / s;
+        quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
+        quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
+        quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
+    }
+}
+
+
+/**
+ * Converts euler angles to a rotation matrix
+ *
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ * @param dcm a 3x3 rotation matrix
+ */
+MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
+{
+    float cosPhi = cosf(roll);
+    float sinPhi = sinf(roll);
+    float cosThe = cosf(pitch);
+    float sinThe = sinf(pitch);
+    float cosPsi = cosf(yaw);
+    float sinPsi = sinf(yaw);
+
+    dcm[0][0] = cosThe * cosPsi;
+    dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
+    dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
+
+    dcm[1][0] = cosThe * sinPsi;
+    dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
+    dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
+
+    dcm[2][0] = -sinThe;
+    dcm[2][1] = sinPhi * cosThe;
+    dcm[2][2] = cosPhi * cosThe;
+}
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mavlink_helpers.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,679 @@
+#ifndef  _MAVLINK_HELPERS_H_
+#define  _MAVLINK_HELPERS_H_
+
+#include "string.h"
+#include "checksum.h"
+#include "mavlink_types.h"
+#include "mavlink_conversions.h"
+
+#ifndef MAVLINK_HELPER
+#define MAVLINK_HELPER
+#endif
+
+/*
+ * Internal function to give access to the channel status for each channel
+ */
+#ifndef MAVLINK_GET_CHANNEL_STATUS
+MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
+{
+#ifdef MAVLINK_EXTERNAL_RX_STATUS
+	// No m_mavlink_status array defined in function,
+	// has to be defined externally
+#else
+	static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+#endif
+	return &m_mavlink_status[chan];
+}
+#endif
+
+/*
+ * Internal function to give access to the channel buffer for each channel
+ */
+#ifndef MAVLINK_GET_CHANNEL_BUFFER
+MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
+{
+	
+#ifdef MAVLINK_EXTERNAL_RX_BUFFER
+	// No m_mavlink_buffer array defined in function,
+	// has to be defined externally
+#else
+	static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
+#endif
+	return &m_mavlink_buffer[chan];
+}
+#endif
+
+/**
+ * @brief Reset the status of a channel.
+ */
+MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
+{
+	mavlink_status_t *status = mavlink_get_channel_status(chan);
+	status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+}
+
+/**
+ * @brief Finalize a MAVLink message with channel assignment
+ *
+ * This function calculates the checksum and sets length and aircraft id correctly.
+ * It assumes that the message id and the payload are already correctly set. This function
+ * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
+ * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
+ *
+ * @param msg Message to finalize
+ * @param system_id Id of the sending (this) system, 1-127
+ * @param length Message length
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
+						      uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
+						      uint8_t chan, uint8_t length)
+#endif
+{
+	// This is only used for the v2 protocol and we silence it here
+	(void)min_length;
+	// This code part is the same for all messages;
+	msg->magic = MAVLINK_STX;
+	msg->len = length;
+	msg->sysid = system_id;
+	msg->compid = component_id;
+	// One sequence number per channel
+	msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
+	mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
+	msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
+	crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
+#if MAVLINK_CRC_EXTRA
+	crc_accumulate(crc_extra, &msg->checksum);
+#endif
+	mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
+	mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
+
+	return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+}
+
+
+/**
+ * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
+						 uint8_t min_length, uint8_t length, uint8_t crc_extra)
+{
+    return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
+}
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, 
+						 uint8_t length)
+{
+	return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
+}
+#endif
+
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
+
+/**
+ * @brief Finalize a MAVLink message with channel assignment and send
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, 
+						    uint8_t min_length, uint8_t length, uint8_t crc_extra)
+#else
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
+#endif
+{
+	uint16_t checksum;
+	uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
+	uint8_t ck[2];
+	mavlink_status_t *status = mavlink_get_channel_status(chan);
+	buf[0] = MAVLINK_STX;
+	buf[1] = length;
+	buf[2] = status->current_tx_seq;
+	buf[3] = mavlink_system.sysid;
+	buf[4] = mavlink_system.compid;
+	buf[5] = msgid;
+	status->current_tx_seq++;
+	checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
+	crc_accumulate_buffer(&checksum, packet, length);
+#if MAVLINK_CRC_EXTRA
+	crc_accumulate(crc_extra, &checksum);
+#endif
+	ck[0] = (uint8_t)(checksum & 0xFF);
+	ck[1] = (uint8_t)(checksum >> 8);
+
+	MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
+	_mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
+	_mavlink_send_uart(chan, packet, length);
+	_mavlink_send_uart(chan, (const char *)ck, 2);
+	MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
+}
+
+/**
+ * @brief re-send a message over a uart channel
+ * this is more stack efficient than re-marshalling the message
+ */
+MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
+{
+	uint8_t ck[2];
+
+	ck[0] = (uint8_t)(msg->checksum & 0xFF);
+	ck[1] = (uint8_t)(msg->checksum >> 8);
+	// XXX use the right sequence here
+
+	MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
+	_mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
+	_mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
+	_mavlink_send_uart(chan, (const char *)ck, 2);
+	MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
+}
+#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+/**
+ * @brief Pack a message to send it over a serial byte stream
+ */
+MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
+{
+	memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
+
+	uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
+
+	ck[0] = (uint8_t)(msg->checksum & 0xFF);
+	ck[1] = (uint8_t)(msg->checksum >> 8);
+
+	return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
+}
+
+union __mavlink_bitfield {
+	uint8_t uint8;
+	int8_t int8;
+	uint16_t uint16;
+	int16_t int16;
+	uint32_t uint32;
+	int32_t int32;
+};
+
+
+MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
+{
+	crc_init(&msg->checksum);
+}
+
+MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
+{
+	crc_accumulate(c, &msg->checksum);
+}
+
+/**
+ * This is a varient of mavlink_frame_char() but with caller supplied
+ * parsing buffers. It is useful when you want to create a MAVLink
+ * parser in a library that doesn't use any global variables
+ *
+ * @param rxmsg    parsing message buffer
+ * @param status   parsing starus buffer 
+ * @param c        The char to parse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @param returnStats if a message was decoded, this is filled with the channel's stats
+ * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <mavlink.h>
+ *
+ * mavlink_message_t msg;
+ * int chan = 0;
+ *
+ *
+ * while(serial.bytesAvailable > 0)
+ * {
+ *   uint8_t byte = serial.getNextByte();
+ *   if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)
+ *     {
+ *     printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
+ *     }
+ * }
+ *
+ *
+ * @endcode
+ */
+MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, 
+                                                 mavlink_status_t* status,
+                                                 uint8_t c, 
+                                                 mavlink_message_t* r_message, 
+                                                 mavlink_status_t* r_mavlink_status)
+{
+        /*
+	  default message crc function. You can override this per-system to
+	  put this data in a different memory segment
+	*/
+#if MAVLINK_CRC_EXTRA
+#ifndef MAVLINK_MESSAGE_CRC
+	static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
+#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
+#endif
+#endif
+
+	/* Enable this option to check the length of each message.
+	   This allows invalid messages to be caught much sooner. Use if the transmission
+	   medium is prone to missing (or extra) characters (e.g. a radio that fades in
+	   and out). Only use if the channel will only contain messages types listed in
+	   the headers.
+	*/
+#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
+#ifndef MAVLINK_MESSAGE_LENGTH
+	static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
+#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
+#endif
+#endif
+
+	int bufferIndex = 0;
+
+	status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
+
+	switch (status->parse_state)
+	{
+	case MAVLINK_PARSE_STATE_UNINIT:
+	case MAVLINK_PARSE_STATE_IDLE:
+		if (c == MAVLINK_STX)
+		{
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+			rxmsg->len = 0;
+			rxmsg->magic = c;
+			mavlink_start_checksum(rxmsg);
+		}
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_STX:
+			if (status->msg_received 
+/* Support shorter buffers than the
+   default maximum packet size */
+#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
+				|| c > MAVLINK_MAX_PAYLOAD_LEN
+#endif
+				)
+		{
+			status->buffer_overrun++;
+			status->parse_error++;
+			status->msg_received = 0;
+			status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+		}
+		else
+		{
+			// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
+			rxmsg->len = c;
+			status->packet_idx = 0;
+			mavlink_update_checksum(rxmsg, c);
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
+		}
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_LENGTH:
+		rxmsg->seq = c;
+		mavlink_update_checksum(rxmsg, c);
+		status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_SEQ:
+		rxmsg->sysid = c;
+		mavlink_update_checksum(rxmsg, c);
+		status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_SYSID:
+		rxmsg->compid = c;
+		mavlink_update_checksum(rxmsg, c);
+		status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_COMPID:
+#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
+	        if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
+		{
+			status->parse_error++;
+			status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+			break;
+	    }
+#endif
+		rxmsg->msgid = c;
+		mavlink_update_checksum(rxmsg, c);
+		if (rxmsg->len == 0)
+		{
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
+		}
+		else
+		{
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
+		}
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_MSGID:
+		_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
+		mavlink_update_checksum(rxmsg, c);
+		if (status->packet_idx == rxmsg->len)
+		{
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
+		}
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
+#if MAVLINK_CRC_EXTRA
+		mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
+#endif
+		if (c != (rxmsg->checksum & 0xFF)) {
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
+		} else {
+			status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
+		}
+                _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
+		break;
+
+	case MAVLINK_PARSE_STATE_GOT_CRC1:
+	case MAVLINK_PARSE_STATE_GOT_BAD_CRC1:
+		if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
+			// got a bad CRC message
+			status->msg_received = MAVLINK_FRAMING_BAD_CRC;
+		} else {
+			// Successfully got message
+			status->msg_received = MAVLINK_FRAMING_OK;
+                }
+                status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+                _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
+                memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
+		break;
+	}
+
+	bufferIndex++;
+	// If a message has been sucessfully decoded, check index
+	if (status->msg_received == MAVLINK_FRAMING_OK)
+	{
+		//while(status->current_seq != rxmsg->seq)
+		//{
+		//	status->packet_rx_drop_count++;
+		//               status->current_seq++;
+		//}
+		status->current_rx_seq = rxmsg->seq;
+		// Initial condition: If no packet has been received so far, drop count is undefined
+		if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
+		// Count this packet as received
+		status->packet_rx_success_count++;
+	}
+
+	r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
+	r_mavlink_status->parse_state = status->parse_state;
+	r_mavlink_status->packet_idx = status->packet_idx;
+	r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
+	r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
+	r_mavlink_status->packet_rx_drop_count = status->parse_error;
+	status->parse_error = 0;
+
+	if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
+		/*
+		  the CRC came out wrong. We now need to overwrite the
+		  msg CRC with the one on the wire so that if the
+		  caller decides to forward the message anyway that
+		  mavlink_msg_to_send_buffer() won't overwrite the
+		  checksum
+		 */
+		r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8);
+	}
+
+	return status->msg_received;
+}
+
+/**
+ * This is a convenience function which handles the complete MAVLink parsing.
+ * the function will parse one byte at a time and return the complete packet once
+ * it could be successfully decoded. This function will return 0, 1 or
+ * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)
+ *
+ * Messages are parsed into an internal buffer (one for each channel). When a complete
+ * message is received it is copies into *returnMsg and the channel's status is
+ * copied into *returnStats.
+ *
+ * @param chan     ID of the current channel. This allows to parse different channels with this function.
+ *                 a channel is not a physical message channel like a serial port, but a logic partition of
+ *                 the communication streams in this case. COMM_NB is the limit for the number of channels
+ *                 on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
+ * @param c        The char to parse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @param returnStats if a message was decoded, this is filled with the channel's stats
+ * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <mavlink.h>
+ *
+ * mavlink_message_t msg;
+ * int chan = 0;
+ *
+ *
+ * while(serial.bytesAvailable > 0)
+ * {
+ *   uint8_t byte = serial.getNextByte();
+ *   if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)
+ *     {
+ *     printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
+ *     }
+ * }
+ *
+ *
+ * @endcode
+ */
+MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
+{
+	return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),
+					 mavlink_get_channel_status(chan),
+					 c,
+					 r_message,
+					 r_mavlink_status);
+}
+
+
+/**
+ * This is a convenience function which handles the complete MAVLink parsing.
+ * the function will parse one byte at a time and return the complete packet once
+ * it could be successfully decoded. This function will return 0 or 1.
+ *
+ * Messages are parsed into an internal buffer (one for each channel). When a complete
+ * message is received it is copies into *returnMsg and the channel's status is
+ * copied into *returnStats.
+ *
+ * @param chan     ID of the current channel. This allows to parse different channels with this function.
+ *                 a channel is not a physical message channel like a serial port, but a logic partition of
+ *                 the communication streams in this case. COMM_NB is the limit for the number of channels
+ *                 on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
+ * @param c        The char to parse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @param returnStats if a message was decoded, this is filled with the channel's stats
+ * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <mavlink.h>
+ *
+ * mavlink_message_t msg;
+ * int chan = 0;
+ *
+ *
+ * while(serial.bytesAvailable > 0)
+ * {
+ *   uint8_t byte = serial.getNextByte();
+ *   if (mavlink_parse_char(chan, byte, &msg))
+ *     {
+ *     printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
+ *     }
+ * }
+ *
+ *
+ * @endcode
+ */
+MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
+{
+    uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
+    if (msg_received == MAVLINK_FRAMING_BAD_CRC) {
+	    // we got a bad CRC. Treat as a parse failure
+	    mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
+	    mavlink_status_t* status = mavlink_get_channel_status(chan);
+	    status->parse_error++;
+	    status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
+	    status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+	    if (c == MAVLINK_STX)
+	    {
+		    status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+		    rxmsg->len = 0;
+		    mavlink_start_checksum(rxmsg);
+	    }
+	    return 0;
+    }
+    return msg_received;
+}
+
+/**
+ * @brief Put a bitfield of length 1-32 bit into the buffer
+ *
+ * @param b the value to add, will be encoded in the bitfield
+ * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
+ * @param packet_index the position in the packet (the index of the first byte to use)
+ * @param bit_index the position in the byte (the index of the first bit to use)
+ * @param buffer packet buffer to write into
+ * @return new position of the last used byte in the buffer
+ */
+MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
+{
+	uint16_t bits_remain = bits;
+	// Transform number into network order
+	int32_t v;
+	uint8_t i_bit_index, i_byte_index, curr_bits_n;
+#if MAVLINK_NEED_BYTE_SWAP
+	union {
+		int32_t i;
+		uint8_t b[4];
+	} bin, bout;
+	bin.i = b;
+	bout.b[0] = bin.b[3];
+	bout.b[1] = bin.b[2];
+	bout.b[2] = bin.b[1];
+	bout.b[3] = bin.b[0];
+	v = bout.i;
+#else
+	v = b;
+#endif
+
+	// buffer in
+	// 01100000 01000000 00000000 11110001
+	// buffer out
+	// 11110001 00000000 01000000 01100000
+
+	// Existing partly filled byte (four free slots)
+	// 0111xxxx
+
+	// Mask n free bits
+	// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
+	// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
+
+	// Shift n bits into the right position
+	// out = in >> n;
+
+	// Mask and shift bytes
+	i_bit_index = bit_index;
+	i_byte_index = packet_index;
+	if (bit_index > 0)
+	{
+		// If bits were available at start, they were available
+		// in the byte before the current index
+		i_byte_index--;
+	}
+
+	// While bits have not been packed yet
+	while (bits_remain > 0)
+	{
+		// Bits still have to be packed
+		// there can be more than 8 bits, so
+		// we might have to pack them into more than one byte
+
+		// First pack everything we can into the current 'open' byte
+		//curr_bits_n = bits_remain << 3; // Equals  bits_remain mod 8
+		//FIXME
+		if (bits_remain <= (uint8_t)(8 - i_bit_index))
+		{
+			// Enough space
+			curr_bits_n = (uint8_t)bits_remain;
+		}
+		else
+		{
+			curr_bits_n = (8 - i_bit_index);
+		}
+		
+		// Pack these n bits into the current byte
+		// Mask out whatever was at that position with ones (xxx11111)
+		buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
+		// Put content to this position, by masking out the non-used part
+		buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
+		
+		// Increment the bit index
+		i_bit_index += curr_bits_n;
+
+		// Now proceed to the next byte, if necessary
+		bits_remain -= curr_bits_n;
+		if (bits_remain > 0)
+		{
+			// Offer another 8 bits / one byte
+			i_byte_index++;
+			i_bit_index = 0;
+		}
+	}
+	
+	*r_bit_index = i_bit_index;
+	// If a partly filled byte is present, mark this as consumed
+	if (i_bit_index != 7) i_byte_index++;
+	return i_byte_index - packet_index;
+}
+
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+// To make MAVLink work on your MCU, define comm_send_ch() if you wish
+// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
+// whole packet at a time
+
+/*
+
+#include "mavlink_types.h"
+
+void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
+{
+    if (chan == MAVLINK_COMM_0)
+    {
+        uart0_transmit(ch);
+    }
+    if (chan == MAVLINK_COMM_1)
+    {
+    	uart1_transmit(ch);
+    }
+}
+ */
+
+MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
+{
+#ifdef MAVLINK_SEND_UART_BYTES
+	/* this is the more efficient approach, if the platform
+	   defines it */
+	MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
+#else
+	/* fallback to one byte at a time */
+	uint16_t i;
+	for (i = 0; i < len; i++) {
+		comm_send_ch(chan, (uint8_t)buf[i]);
+	}
+#endif
+}
+#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+#endif /* _MAVLINK_HELPERS_H_ */
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mavlink_types.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,229 @@
+#ifndef MAVLINK_TYPES_H_
+#define MAVLINK_TYPES_H_
+
+// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
+#if (defined _MSC_VER) && (_MSC_VER < 1600)
+#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
+#endif
+
+#include <stdint.h>
+
+// Macro to define packed structures
+#ifdef __GNUC__
+  #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
+#else
+  #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
+#endif
+
+#ifndef MAVLINK_MAX_PAYLOAD_LEN
+// it is possible to override this, but be careful!
+#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
+#endif
+
+#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
+#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
+#define MAVLINK_NUM_CHECKSUM_BYTES 2
+#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
+
+#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
+
+#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
+#define MAVLINK_EXTENDED_HEADER_LEN 14
+
+#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)
+  /* full fledged 32bit++ OS */
+  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
+#else
+  /* small microcontrollers */
+  #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
+#endif
+
+#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
+
+
+/**
+ * Old-style 4 byte param union
+ *
+ * This struct is the data format to be used when sending
+ * parameters. The parameter should be copied to the native
+ * type (without type conversion)
+ * and re-instanted on the receiving side using the
+ * native type as well.
+ */
+MAVPACKED(
+typedef struct param_union {
+	union {
+		float param_float;
+		int32_t param_int32;
+		uint32_t param_uint32;
+		int16_t param_int16;
+		uint16_t param_uint16;
+		int8_t param_int8;
+		uint8_t param_uint8;
+		uint8_t bytes[4];
+	};
+	uint8_t type;
+}) mavlink_param_union_t;
+
+
+/**
+ * New-style 8 byte param union
+ * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.
+ * The mavlink_param_union_double_t will be treated as a little-endian structure.
+ *
+ * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.
+ * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the
+ * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.
+ * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,
+ * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86,
+ * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
+ * and the bits pulled out using the shifts/masks.
+*/
+MAVPACKED(
+typedef struct param_union_extended {
+    union {
+    struct {
+        uint8_t is_double:1;
+        uint8_t mavlink_type:7;
+        union {
+            char c;
+            uint8_t uint8;
+            int8_t int8;
+            uint16_t uint16;
+            int16_t int16;
+            uint32_t uint32;
+            int32_t int32;
+            float f;
+            uint8_t align[7];
+        };
+    };
+    uint8_t data[8];
+    };
+}) mavlink_param_union_double_t;
+
+/**
+ * This structure is required to make the mavlink_send_xxx convenience functions
+ * work, as it tells the library what the current system and component ID are.
+ */
+MAVPACKED(
+typedef struct __mavlink_system {
+    uint8_t sysid;   ///< Used by the MAVLink message_xx_send() convenience function
+    uint8_t compid;  ///< Used by the MAVLink message_xx_send() convenience function
+}) mavlink_system_t;
+
+MAVPACKED(
+typedef struct __mavlink_message {
+	uint16_t checksum; ///< sent at end of packet
+	uint8_t magic;   ///< protocol magic marker
+	uint8_t len;     ///< Length of payload
+	uint8_t seq;     ///< Sequence of packet
+	uint8_t sysid;   ///< ID of message sender system/aircraft
+	uint8_t compid;  ///< ID of the message sender component
+	uint8_t msgid;   ///< ID of message in payload
+	uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
+}) mavlink_message_t;
+
+MAVPACKED(
+typedef struct __mavlink_extended_message {
+       mavlink_message_t base_msg;
+       int32_t extended_payload_len;   ///< Length of extended payload if any
+       uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
+}) mavlink_extended_message_t;
+
+typedef enum {
+	MAVLINK_TYPE_CHAR     = 0,
+	MAVLINK_TYPE_UINT8_T  = 1,
+	MAVLINK_TYPE_INT8_T   = 2,
+	MAVLINK_TYPE_UINT16_T = 3,
+	MAVLINK_TYPE_INT16_T  = 4,
+	MAVLINK_TYPE_UINT32_T = 5,
+	MAVLINK_TYPE_INT32_T  = 6,
+	MAVLINK_TYPE_UINT64_T = 7,
+	MAVLINK_TYPE_INT64_T  = 8,
+	MAVLINK_TYPE_FLOAT    = 9,
+	MAVLINK_TYPE_DOUBLE   = 10
+} mavlink_message_type_t;
+
+#define MAVLINK_MAX_FIELDS 64
+
+typedef struct __mavlink_field_info {
+        const char *name;                 // name of this field
+        const char *print_format;         // printing format hint, or NULL
+        mavlink_message_type_t type;      // type of this field
+        unsigned int array_length;        // if non-zero, field is an array
+        unsigned int wire_offset;         // offset of each field in the payload
+        unsigned int structure_offset;    // offset in a C structure
+} mavlink_field_info_t;
+
+// note that in this structure the order of fields is the order
+// in the XML file, not necessary the wire order
+typedef struct __mavlink_message_info {
+	const char *name;                                      // name of the message
+	unsigned num_fields;                                   // how many fields in this message
+	mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];       // field information
+} mavlink_message_info_t;
+
+#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
+#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
+
+// checksum is immediately after the payload bytes
+#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
+#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
+
+typedef enum {
+    MAVLINK_COMM_0,
+    MAVLINK_COMM_1,
+    MAVLINK_COMM_2,
+    MAVLINK_COMM_3
+} mavlink_channel_t;
+
+/*
+ * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
+ * of buffers they will use. If more are used, then the result will be
+ * a stack overrun
+ */
+#ifndef MAVLINK_COMM_NUM_BUFFERS
+#if (defined linux) | (defined __linux) | (defined  __MACH__) | (defined _WIN32)
+# define MAVLINK_COMM_NUM_BUFFERS 16
+#else
+# define MAVLINK_COMM_NUM_BUFFERS 4
+#endif
+#endif
+
+typedef enum {
+    MAVLINK_PARSE_STATE_UNINIT=0,
+    MAVLINK_PARSE_STATE_IDLE,
+    MAVLINK_PARSE_STATE_GOT_STX,
+    MAVLINK_PARSE_STATE_GOT_SEQ,
+    MAVLINK_PARSE_STATE_GOT_LENGTH,
+    MAVLINK_PARSE_STATE_GOT_SYSID,
+    MAVLINK_PARSE_STATE_GOT_COMPID,
+    MAVLINK_PARSE_STATE_GOT_MSGID,
+    MAVLINK_PARSE_STATE_GOT_PAYLOAD,
+    MAVLINK_PARSE_STATE_GOT_CRC1,
+    MAVLINK_PARSE_STATE_GOT_BAD_CRC1
+} mavlink_parse_state_t; ///< The state machine for the comm parser
+
+typedef enum {
+    MAVLINK_FRAMING_INCOMPLETE=0,
+    MAVLINK_FRAMING_OK=1,
+    MAVLINK_FRAMING_BAD_CRC=2
+} mavlink_framing_t;
+
+typedef struct __mavlink_status {
+    uint8_t msg_received;               ///< Number of received messages
+    uint8_t buffer_overrun;             ///< Number of buffer overruns
+    uint8_t parse_error;                ///< Number of parse errors
+    mavlink_parse_state_t parse_state;  ///< Parsing state machine
+    uint8_t packet_idx;                 ///< Index in current packet
+    uint8_t current_rx_seq;             ///< Sequence number of last packet received
+    uint8_t current_tx_seq;             ///< Sequence number of last packet sent
+    uint16_t packet_rx_success_count;   ///< Received packets
+    uint16_t packet_rx_drop_count;      ///< Number of packet drops
+} mavlink_status_t;
+
+#define MAVLINK_BIG_ENDIAN 0
+#define MAVLINK_LITTLE_ENDIAN 1
+
+#endif /* MAVLINK_TYPES_H_ */
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/protocol.h	Fri Jan 20 13:20:58 2017 +0000
@@ -0,0 +1,340 @@
+#ifndef  _MAVLINK_PROTOCOL_H_
+#define  _MAVLINK_PROTOCOL_H_
+
+#include "string.h"
+#include "mavlink_types.h"
+
+/* 
+   If you want MAVLink on a system that is native big-endian,
+   you need to define NATIVE_BIG_ENDIAN
+*/
+#ifdef NATIVE_BIG_ENDIAN
+# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
+#else
+# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
+#endif
+
+#ifndef MAVLINK_STACK_BUFFER
+#define MAVLINK_STACK_BUFFER 0
+#endif
+
+#ifndef MAVLINK_AVOID_GCC_STACK_BUG
+# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
+#endif
+
+#ifndef MAVLINK_ASSERT
+#define MAVLINK_ASSERT(x)
+#endif
+
+#ifndef MAVLINK_START_UART_SEND
+#define MAVLINK_START_UART_SEND(chan, length)
+#endif
+
+#ifndef MAVLINK_END_UART_SEND
+#define MAVLINK_END_UART_SEND(chan, length)
+#endif
+
+/* option to provide alternative implementation of mavlink_helpers.h */
+#ifdef MAVLINK_SEPARATE_HELPERS
+
+    #define MAVLINK_HELPER
+
+    /* decls in sync with those in mavlink_helpers.h */
+    #ifndef MAVLINK_GET_CHANNEL_STATUS
+    MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
+    #endif
+    MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
+    #if MAVLINK_CRC_EXTRA
+    MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                          uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra);
+    MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                     uint8_t min_length, uint8_t length, uint8_t crc_extra);
+    #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+    MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
+                                                        uint8_t min_length, uint8_t length, uint8_t crc_extra);
+    #endif
+    #else
+    MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                          uint8_t chan, uint8_t length);
+    MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                     uint8_t length);
+    #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+    MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
+    #endif
+    #endif // MAVLINK_CRC_EXTRA
+    MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
+    MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
+    MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
+    MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, 
+						     mavlink_status_t* status,
+						     uint8_t c, 
+						     mavlink_message_t* r_message, 
+						     mavlink_status_t* r_mavlink_status);
+    MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
+    MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
+    MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
+                               uint8_t* r_bit_index, uint8_t* buffer);
+    #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+    MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
+    MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
+    #endif
+
+#else
+
+    #define MAVLINK_HELPER static inline
+    #include "mavlink_helpers.h"
+
+#endif // MAVLINK_SEPARATE_HELPERS
+
+/**
+ * @brief Get the required buffer size for this message
+ */
+static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
+{
+	return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+static inline void byte_swap_2(char *dst, const char *src)
+{
+	dst[0] = src[1];
+	dst[1] = src[0];
+}
+static inline void byte_swap_4(char *dst, const char *src)
+{
+	dst[0] = src[3];
+	dst[1] = src[2];
+	dst[2] = src[1];
+	dst[3] = src[0];
+}
+static inline void byte_swap_8(char *dst, const char *src)
+{
+	dst[0] = src[7];
+	dst[1] = src[6];
+	dst[2] = src[5];
+	dst[3] = src[4];
+	dst[4] = src[3];
+	dst[5] = src[2];
+	dst[6] = src[1];
+	dst[7] = src[0];
+}
+#elif !MAVLINK_ALIGNED_FIELDS
+static inline void byte_copy_2(char *dst, const char *src)
+{
+	dst[0] = src[0];
+	dst[1] = src[1];
+}
+static inline void byte_copy_4(char *dst, const char *src)
+{
+	dst[0] = src[0];
+	dst[1] = src[1];
+	dst[2] = src[2];
+	dst[3] = src[3];
+}
+static inline void byte_copy_8(char *dst, const char *src)
+{
+	memcpy(dst, src, 8);
+}
+#endif
+
+#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
+#define _mav_put_int8_t(buf, wire_offset, b)  buf[wire_offset] = (int8_t)b
+#define _mav_put_char(buf, wire_offset, b)    buf[wire_offset] = b
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int16_t(buf, wire_offset, b)  byte_swap_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int32_t(buf, wire_offset, b)  byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int64_t(buf, wire_offset, b)  byte_swap_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_float(buf, wire_offset, b)    byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_double(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
+#elif !MAVLINK_ALIGNED_FIELDS
+#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int16_t(buf, wire_offset, b)  byte_copy_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int32_t(buf, wire_offset, b)  byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int64_t(buf, wire_offset, b)  byte_copy_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_float(buf, wire_offset, b)    byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_double(buf, wire_offset, b)   byte_copy_8(&buf[wire_offset], (const char *)&b)
+#else
+#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
+#define _mav_put_int16_t(buf, wire_offset, b)  *(int16_t *)&buf[wire_offset] = b
+#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
+#define _mav_put_int32_t(buf, wire_offset, b)  *(int32_t *)&buf[wire_offset] = b
+#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
+#define _mav_put_int64_t(buf, wire_offset, b)  *(int64_t *)&buf[wire_offset] = b
+#define _mav_put_float(buf, wire_offset, b)    *(float *)&buf[wire_offset] = b
+#define _mav_put_double(buf, wire_offset, b)   *(double *)&buf[wire_offset] = b
+#endif
+
+/*
+  like memcpy(), but if src is NULL, do a memset to zero
+*/
+static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
+{
+	if (src == NULL) {
+		memset(dest, 0, n);
+	} else {
+		memcpy(dest, src, n);
+	}
+}
+
+/*
+ * Place a char array into a buffer
+ */
+static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
+{
+	mav_array_memcpy(&buf[wire_offset], b, array_length);
+
+}
+
+/*
+ * Place a uint8_t array into a buffer
+ */
+static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
+{
+	mav_array_memcpy(&buf[wire_offset], b, array_length);
+
+}
+
+/*
+ * Place a int8_t array into a buffer
+ */
+static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
+{
+	mav_array_memcpy(&buf[wire_offset], b, array_length);
+
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_PUT_ARRAY(TYPE, V) \
+static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
+{ \
+	if (b == NULL) { \
+		memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
+	} else { \
+		uint16_t i; \
+		for (i=0; i<array_length; i++) { \
+			_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
+		} \
+	} \
+}
+#else
+#define _MAV_PUT_ARRAY(TYPE, V)					\
+static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
+{ \
+	mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
+}
+#endif
+
+_MAV_PUT_ARRAY(uint16_t, u16)
+_MAV_PUT_ARRAY(uint32_t, u32)
+_MAV_PUT_ARRAY(uint64_t, u64)
+_MAV_PUT_ARRAY(int16_t,  i16)
+_MAV_PUT_ARRAY(int32_t,  i32)
+_MAV_PUT_ARRAY(int64_t,  i64)
+_MAV_PUT_ARRAY(float,    f)
+_MAV_PUT_ARRAY(double,   d)
+
+#define _MAV_RETURN_char(msg, wire_offset)             (const char)_MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_int8_t(msg, wire_offset)   (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
+
+_MAV_MSG_RETURN_TYPE(uint16_t, 2)
+_MAV_MSG_RETURN_TYPE(int16_t,  2)
+_MAV_MSG_RETURN_TYPE(uint32_t, 4)
+_MAV_MSG_RETURN_TYPE(int32_t,  4)
+_MAV_MSG_RETURN_TYPE(uint64_t, 8)
+_MAV_MSG_RETURN_TYPE(int64_t,  8)
+_MAV_MSG_RETURN_TYPE(float,    4)
+_MAV_MSG_RETURN_TYPE(double,   8)
+
+#elif !MAVLINK_ALIGNED_FIELDS
+#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
+
+_MAV_MSG_RETURN_TYPE(uint16_t, 2)
+_MAV_MSG_RETURN_TYPE(int16_t,  2)
+_MAV_MSG_RETURN_TYPE(uint32_t, 4)
+_MAV_MSG_RETURN_TYPE(int32_t,  4)
+_MAV_MSG_RETURN_TYPE(uint64_t, 8)
+_MAV_MSG_RETURN_TYPE(int64_t,  8)
+_MAV_MSG_RETURN_TYPE(float,    4)
+_MAV_MSG_RETURN_TYPE(double,   8)
+#else // nicely aligned, no swap
+#define _MAV_MSG_RETURN_TYPE(TYPE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
+
+_MAV_MSG_RETURN_TYPE(uint16_t)
+_MAV_MSG_RETURN_TYPE(int16_t)
+_MAV_MSG_RETURN_TYPE(uint32_t)
+_MAV_MSG_RETURN_TYPE(int32_t)
+_MAV_MSG_RETURN_TYPE(uint64_t)
+_MAV_MSG_RETURN_TYPE(int64_t)
+_MAV_MSG_RETURN_TYPE(float)
+_MAV_MSG_RETURN_TYPE(double)
+#endif // MAVLINK_NEED_BYTE_SWAP
+
+static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, 
+						     uint8_t array_length, uint8_t wire_offset)
+{
+	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+	return array_length;
+}
+
+static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, 
+							uint8_t array_length, uint8_t wire_offset)
+{
+	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+	return array_length;
+}
+
+static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value, 
+						       uint8_t array_length, uint8_t wire_offset)
+{
+	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+	return array_length;
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_RETURN_ARRAY(TYPE, V) \
+static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
+							 uint8_t array_length, uint8_t wire_offset) \
+{ \
+	uint16_t i; \
+	for (i=0; i<array_length; i++) { \
+		value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
+	} \
+	return array_length*sizeof(value[0]); \
+}
+#else
+#define _MAV_RETURN_ARRAY(TYPE, V)					\
+static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
+							 uint8_t array_length, uint8_t wire_offset) \
+{ \
+	memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
+	return array_length*sizeof(TYPE); \
+}
+#endif
+
+_MAV_RETURN_ARRAY(uint16_t, u16)
+_MAV_RETURN_ARRAY(uint32_t, u32)
+_MAV_RETURN_ARRAY(uint64_t, u64)
+_MAV_RETURN_ARRAY(int16_t,  i16)
+_MAV_RETURN_ARRAY(int32_t,  i32)
+_MAV_RETURN_ARRAY(int64_t,  i64)
+_MAV_RETURN_ARRAY(float,    f)
+_MAV_RETURN_ARRAY(double,   d)
+
+#endif // _MAVLINK_PROTOCOL_H_
+