Projet Drone de surveillance du labo TRSE (INGESUP)

Dependencies:   mbed PID ADXL345 Camera_LS_Y201 ITG3200 RangeFinder mbos xbee_lib Motor Servo

Files at this revision

API Documentation at this revision

Comitter:
Gaetan
Date:
Wed Mar 19 09:27:19 2014 +0000
Parent:
34:4466839f5bb7
Child:
36:1bbd2fb7d2c8
Commit message:
Ajout de la librairie MavLink avec un main de test pour QGroundControl.; Pour l'instant seul le heartbeat fonctionne;

Changed in this revision

Module_Asservissement/Sous_Module_Mouvement/Module_Mouvement.cpp Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVLink_API/MAVLink_API.cpp Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVLink_API/MAVLink_API.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ardupilotmega/ardupilotmega.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ardupilotmega/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ardupilotmega/mavlink_msg_sensor_offsets.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/checksum.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/common.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_action.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_action_ack.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_attitude.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_auth_key.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_boot.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_change_operator_control.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_change_operator_control_ack.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_command.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_command_ack.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_control_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_debug.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_debug_vect.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_full_state.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_global_position.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_global_position_int.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_local_origin_set.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw_int.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw_ugv.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_set_global_origin.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_gps_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_hil_controls.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_hil_state.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_local_position.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_local_position_setpoint.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_local_position_setpoint_set.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_manual_control.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_named_value_float.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_named_value_int.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_nav_controller_output.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_object_detection_event.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_optical_flow.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_param_request_list.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_param_request_read.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_param_set.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_param_value.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_ping.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_position_target.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_raw_imu.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_raw_pressure.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_override.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_raw.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_scaled.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_request_data_stream.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_safety_allowed_area.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_safety_set_allowed_area.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_scaled_imu.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_scaled_pressure.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_servo_output_raw.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_altitude.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_mode.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_nav_mode.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_state_correction.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_statustext.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_sys_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_system_time.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_system_time_utc.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_vfr_hud.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_ack.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_clear_all.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_count.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_current.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_reached.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_request.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_request_list.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_set_current.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/mavlink_bridge.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/mavlink_types.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/minimal/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/minimal/mavlink_msg_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/minimal/minimal.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_attitude_control.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_aux_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_brief_feature.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_encapsulated_data.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_global_vision_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_available.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_trigger_control.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_triggered.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_marker.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_pattern_detected.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_point_of_interest.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_offset_set.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_raw_aux.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_set_cam_shutter.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vision_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vision_speed_estimate.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_visual_odometry.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_info.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/pixhawk/pixhawk.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/protocol.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_air_data.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_cpu_load.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_data_log.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_diagnostic.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_gps_date_time.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_mid_lvl_cmds.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_sensor_bias.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_slugs_action.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/mavlink_msg_slugs_navigation.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/slugs/slugs.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/mavlink.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/mavlink_msg_nav_filter_bias.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/mavlink_msg_radio_calibration.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/mavlink_msg_request_rc_channels.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/mavlink_msg_ualberta_sys_status.h Show annotated file Show diff for this revision Revisions of this file
Module_Communication/MAVlink/include/ualberta/ualberta.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/Module_Asservissement/Sous_Module_Mouvement/Module_Mouvement.cpp	Wed Mar 19 09:18:53 2014 +0000
+++ b/Module_Asservissement/Sous_Module_Mouvement/Module_Mouvement.cpp	Wed Mar 19 09:27:19 2014 +0000
@@ -26,7 +26,7 @@
  
 
 DigitalOut led1(LED1);
-Serial pc(USBTX, USBRX);
+extern Serial pc;
  
  /* CONSRTRUCTEUR(S) */
  ModuleMouvement::ModuleMouvement()
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVLink_API/MAVLink_API.cpp	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,123 @@
+#include "MAVLink_API.h"
+
+#if DEBUG
+Serial debug(USBTX, USBRX);
+#endif
+
+mavLink_API::mavLink_API(float heartbeat_freq){
+    mavlink_system.sysid = 20;                   ///< ID 20 for this airplane
+//mavlink_system.compid = MAV_COMP_ID_IMU;     ///< The component sending the message is the IMU, it could be also a Linux process
+    mavlink_system.compid = MAV_COMP_ID_IMU;
+    mavlink_system.type = MAV_QUADROTOR;
+    
+    buf = new uint8_t[MAVLINK_MAX_PACKET_LEN];
+    messageReadyToBeSent = false;
+    heartBeatTicker.attach(this, &mavLink_API::sendHeartBeat, heartbeat_freq);
+#if DEBUG
+    debug.printf("Object MAVLinK_API instanciated\n");
+#endif
+}
+
+mavLink_API::~mavLink_API(){
+    
+}
+
+void mavLink_API::sendHeartBeat()
+{
+    
+#if DEBUG
+    debug.printf("Send heartBeat\n");
+#endif
+    uint8_t system_type = MAV_QUADROTOR;
+    uint8_t autopilot_type = MAV_AUTOPILOT_GENERIC;
+ 
+    uint8_t system_mode = MAV_MODE_READY; ///< Booting up
+    uint32_t custom_mode = 0;                 ///< Custom mode, can be defined by user/adopter
+    uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight
+ 
+// Initialize the required buffers
+    mavlink_message_t msg;
+ 
+// Pack the message
+    mavlink_msg_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, system_type, autopilot_type, system_mode, custom_mode, system_state);
+ 
+// Copy the message to the send buffer
+    len = mavlink_msg_to_send_buffer(buf, &msg);
+    messageReadyToBeSent = true;
+}
+
+
+int mavLink_API::getMessage(char received_char){
+#if DEBUG
+    //debug.printf("%X ", received_char);
+#endif
+    
+    if(mavlink_parse_char(MAVLINK_COMM_0, received_char, &received_msg, &mavlink_status)){
+        //now handle the message received
+        
+#if DEBUG
+        //debug.printf("\n");
+        debug.printf("Received MavLink message :\n");
+        printMavLinkMessage(received_msg);
+#endif
+        switch(received_msg.msgid)
+        {
+            case MAVLINK_MSG_ID_HEARTBEAT:
+#if DEBUG
+            debug.printf("received heartbeat\n");
+#endif
+            break;
+            case MAVLINK_MSG_ID_COMMAND:
+#if DEBUG
+            debug.printf("received command\n");
+#endif
+            break;
+            case MAVLINK_MSG_ID_SET_MODE:
+#if DEBUG
+            debug.printf("received set mode\n");
+            //target_system   uint8_t The system setting the mode
+            //base_mode   uint8_t The new base mode
+            //custom_mode
+#endif
+            break;
+            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
+#if DEBUG
+            debug.printf("received param request list\n");
+#endif
+            break;
+            default:
+#if DEBUG
+
+#endif
+            break;
+         }
+        
+    }
+    else return 0;
+    return 1;
+}
+int mavLink_API::handleMessage()
+{
+    return 1;
+}
+
+#if DEBUG
+void mavLink_API::printMavLinkMessage(mavlink_message_t message)
+{
+    debug.printf("Len :%d\n", message.len);     ///< Length of payload
+    debug.printf("Seq :%d\n", message.seq);     ///< Sequence of packet
+    debug.printf("Sysid :%d\n", message.sysid);   ///< ID of message sender system/aircraft
+    debug.printf("Compid :%d\n", message.compid);  ///< ID of the message sender component
+    debug.printf("MsgId :%d\n", message.msgid);   ///< ID of message in payload
+    for(int i = 0 ; i < message.len ; i++){
+        debug.printf("%X ", message.payload[i]);
+    }
+    debug.printf("\n");
+    debug.printf("CK_a :%d\n", message.ck_a);    ///< Checksum high byte
+    debug.printf("CK_b :%d\n", message.ck_b);    ///< Checksum low byte
+}
+#endif
+
+int createMessage(int messageID, void* data){
+    return 1;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVLink_API/MAVLink_API.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,38 @@
+#ifndef MAVLINK_API_H
+#define MAVLINK_API_H
+
+#include "mbed.h"
+#include "MAVlink/include/common/common.h"
+
+#define DEBUG 1
+
+class mavLink_API
+{
+private:
+    Ticker heartBeatTicker;
+    mavlink_system_t mavlink_system;
+    mavlink_status_t mavlink_status;
+
+    mavlink_message_t send_msg;
+    mavlink_message_t received_msg;
+    
+public:    
+
+    bool messageReadyToBeSent;
+    uint8_t *buf;
+    uint16_t len;
+    
+    mavLink_API(float heartbeat_freq);
+    ~mavLink_API();
+    
+    int getMessage(char received_char);
+    int handleMessage();
+    int createMessage(int messageID, void* data);
+    void sendHeartBeat();
+#if DEBUG
+    void printMavLinkMessage(mavlink_message_t message);
+#endif
+    
+};
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ardupilotmega/ardupilotmega.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,48 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://qgroundcontrol.org/mavlink/
+ *	 Generated on Saturday, August 13 2011, 08:44 UTC
+ */
+#ifndef ARDUPILOTMEGA_H
+#define ARDUPILOTMEGA_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_ARDUPILOTMEGA
+
+
+#include "../common/common.h"
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+// ENUM DEFINITIONS
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_sensor_offsets.h"
+#include "./mavlink_msg_set_mag_offsets.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ardupilotmega/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Saturday, August 13 2011, 08:44 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "ardupilotmega.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ardupilotmega/mavlink_msg_sensor_offsets.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,342 @@
+// MESSAGE SENSOR_OFFSETS PACKING
+
+#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
+
+typedef struct __mavlink_sensor_offsets_t 
+{
+	int16_t mag_ofs_x; ///< magnetometer X offset
+	int16_t mag_ofs_y; ///< magnetometer Y offset
+	int16_t mag_ofs_z; ///< magnetometer Z offset
+	float mag_declination; ///< magnetic declination (radians)
+	int32_t raw_press; ///< raw pressure from barometer
+	int32_t raw_temp; ///< raw temperature from barometer
+	float gyro_cal_x; ///< gyro X calibration
+	float gyro_cal_y; ///< gyro Y calibration
+	float gyro_cal_z; ///< gyro Z calibration
+	float accel_cal_x; ///< accel X calibration
+	float accel_cal_y; ///< accel Y calibration
+	float accel_cal_z; ///< accel Z calibration
+
+} mavlink_sensor_offsets_t;
+
+
+
+/**
+ * @brief Pack a sensor_offsets 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 mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ * @param mag_declination magnetic declination (radians)
+ * @param raw_press raw pressure from barometer
+ * @param raw_temp raw temperature from barometer
+ * @param gyro_cal_x gyro X calibration
+ * @param gyro_cal_y gyro Y calibration
+ * @param gyro_cal_z gyro Z calibration
+ * @param accel_cal_x accel X calibration
+ * @param accel_cal_y accel Y calibration
+ * @param accel_cal_z accel Z calibration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
+
+	i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
+	i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
+	i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
+	i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
+	i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
+	i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
+	i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
+	i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
+	i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
+	i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
+	i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
+	i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a sensor_offsets message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ * @param mag_declination magnetic declination (radians)
+ * @param raw_press raw pressure from barometer
+ * @param raw_temp raw temperature from barometer
+ * @param gyro_cal_x gyro X calibration
+ * @param gyro_cal_y gyro Y calibration
+ * @param gyro_cal_z gyro Z calibration
+ * @param accel_cal_x accel X calibration
+ * @param accel_cal_y accel Y calibration
+ * @param accel_cal_z accel Z calibration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
+
+	i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
+	i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
+	i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
+	i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
+	i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
+	i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
+	i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
+	i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
+	i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
+	i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
+	i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
+	i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a sensor_offsets struct into a 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 sensor_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+	return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+}
+
+/**
+ * @brief Send a sensor_offsets message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ * @param mag_declination magnetic declination (radians)
+ * @param raw_press raw pressure from barometer
+ * @param raw_temp raw temperature from barometer
+ * @param gyro_cal_x gyro X calibration
+ * @param gyro_cal_y gyro Y calibration
+ * @param gyro_cal_z gyro Z calibration
+ * @param accel_cal_x accel X calibration
+ * @param accel_cal_y accel Y calibration
+ * @param accel_cal_z accel Z calibration
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_sensor_offsets_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SENSOR_OFFSETS UNPACKING
+
+/**
+ * @brief Get field mag_ofs_x from sensor_offsets message
+ *
+ * @return magnetometer X offset
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field mag_ofs_y from sensor_offsets message
+ *
+ * @return magnetometer Y offset
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field mag_ofs_z from sensor_offsets message
+ *
+ * @return magnetometer Z offset
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field mag_declination from sensor_offsets message
+ *
+ * @return magnetic declination (radians)
+ */
+static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field raw_press from sensor_offsets message
+ *
+ * @return raw pressure from barometer
+ */
+static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field raw_temp from sensor_offsets message
+ *
+ * @return raw temperature from barometer
+ */
+static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field gyro_cal_x from sensor_offsets message
+ *
+ * @return gyro X calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyro_cal_y from sensor_offsets message
+ *
+ * @return gyro Y calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyro_cal_z from sensor_offsets message
+ *
+ * @return gyro Z calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field accel_cal_x from sensor_offsets message
+ *
+ * @return accel X calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field accel_cal_y from sensor_offsets message
+ *
+ * @return accel Y calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field accel_cal_z from sensor_offsets message
+ *
+ * @return accel Z calibration
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a sensor_offsets message into a struct
+ *
+ * @param msg The message to decode
+ * @param sensor_offsets C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
+{
+	sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
+	sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
+	sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
+	sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
+	sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
+	sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
+	sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
+	sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
+	sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
+	sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
+	sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
+	sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,178 @@
+// MESSAGE SET_MAG_OFFSETS PACKING
+
+#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
+
+typedef struct __mavlink_set_mag_offsets_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	int16_t mag_ofs_x; ///< magnetometer X offset
+	int16_t mag_ofs_y; ///< magnetometer Y offset
+	int16_t mag_ofs_z; ///< magnetometer Z offset
+
+} mavlink_set_mag_offsets_t;
+
+
+
+/**
+ * @brief Pack a set_mag_offsets 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 target_system System ID
+ * @param target_component Component ID
+ * @param mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
+	i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
+	i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_mag_offsets message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
+	i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
+	i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_mag_offsets struct into a 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 set_mag_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+	return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+}
+
+/**
+ * @brief Send a set_mag_offsets message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param mag_ofs_x magnetometer X offset
+ * @param mag_ofs_y magnetometer Y offset
+ * @param mag_ofs_z magnetometer Z offset
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_mag_offsets_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_MAG_OFFSETS UNPACKING
+
+/**
+ * @brief Get field target_system from set_mag_offsets message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from set_mag_offsets message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field mag_ofs_x from set_mag_offsets message
+ *
+ * @return magnetometer X offset
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field mag_ofs_y from set_mag_offsets message
+ *
+ * @return magnetometer Y offset
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field mag_ofs_z from set_mag_offsets message
+ *
+ * @return magnetometer Z offset
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a set_mag_offsets message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_mag_offsets C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+	set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
+	set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
+	set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
+	set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
+	set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/checksum.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,95 @@
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef _CHECKSUM_H_
+#define _CHECKSUM_H_
+
+#include "inttypes.h"
+
+
+/**
+ *
+ *  CALCULATE THE CHECKSUM
+ *
+ */
+
+#define X25_INIT_CRC 0xffff
+#define X25_VALIDATE_CRC 0xf0b8
+
+/**
+ * @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);
+}
+
+/**
+ * @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(uint8_t* pBuffer, int length)
+{
+
+        // For a "message" of length bytes contained in the unsigned char array
+        // pointed to by pBuffer, calculate the CRC
+        // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed
+
+        uint16_t crcTmp;
+        //uint16_t tmp;
+        uint8_t* pTmp;
+		int i;
+
+        pTmp=pBuffer;
+        
+
+        /* init crcTmp */
+        crc_init(&crcTmp);
+
+        for (i = 0; i < length; i++){
+                crc_accumulate(*pTmp++, &crcTmp);
+        }
+
+        /* This is currently not needed, as only the checksum over payload should be computed
+        tmp = crcTmp;
+        crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp);
+        crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp);
+        *checkConst = tmp;
+        */
+        return(crcTmp);
+}
+
+
+
+
+#endif /* _CHECKSUM_H_ */
+
+#ifdef __cplusplus
+}
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/common.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,176 @@
+/** @file
+ *    @brief MAVLink comm protocol.
+ *    @see http://qgroundcontrol.org/mavlink/
+ *     Generated on Sunday, September 11 2011, 13:52 UTC
+ */
+#ifndef COMMON_H
+#define COMMON_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_COMMON
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+// ENUM DEFINITIONS
+
+/** @brief  Commands to be executed by the MAV. They can be executed on user request,       or as part of a mission script. If the action is used in a mission, the parameter mapping       to the waypoint/mission message is as follows:       Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what       ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */
+enum MAV_CMD
+{
+    MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. | Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) | Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached) | 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. | Desired yaw angle at waypoint (rotary wing) | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time | Empty | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns | Turns | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds | Seconds (decimal) | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location | Empty | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_NAV_LAND=21, /* Land at location | Empty | Empty | Empty | Desired yaw angle. | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand | Minimum pitch (if airspeed sensor present), desired pitch without sensor | Empty | Empty | Yaw angle (if magnetometer present), ignored without magnetometer | Latitude | Longitude | Altitude | */
+    MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. | Region of intereset mode. (see MAV_ROI enum) | Waypoint index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple ROI's) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | */
+    MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. | 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning | 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid | Empty | Yaw angle at goal, in compass degrees, [0..360] | Latitude/X of goal | Longitude/Y of goal | Altitude/Z of goal | */
+    MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. | Delay in seconds (decimal) | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. | Descent / Ascend rate (m/s) | Empty | Empty | Empty | Empty | Empty | Finish Altitude | */
+    MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. | Distance (meters) | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. | target angle: [0-360], 0 is north | speed during yaw change:[deg per second] | direction: negative: counter clockwise, positive: clockwise [-1,1] | relative offset or absolute angle: [ 1,0] | Empty | Empty | Empty | */
+    MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_SET_MODE=176, /* Set system mode. | Mode, as defined by ENUM MAV_MODE | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times | Sequence number | Repeat count | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. | Speed type (0=Airspeed, 1=Ground Speed) | Speed (m/s, -1 indicates no change) | Throttle ( Percent, -1 indicates no change) | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. | Use current (1=use current location, 0=use specified location) | Empty | Empty | Empty | Latitude | Longitude | Altitude | */
+    MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. | Parameter number | Parameter value | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. | Relay number | Setting (1=on, 0=off, others possible depending on system hardware) | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. | Relay number | Cycle count | Cycle time (seconds, decimal) | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Cycle count | Cycle time (seconds) | Empty | Empty | Empty | */
+    MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera capturing. | Camera ID (-1 for all) | Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw | Transmission mode: 0: video stream, >0: single images every n seconds (decimal) | Recording: 0: disabled, 1: enabled compressed, 2: enabled raw | Empty | Empty | Empty | */
+    MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various devices such as cameras. | Region of interest mode. (see MAV_ROI enum) | Waypoint index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple cameras etc.) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | */
+    MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | */
+    MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. | Gyro calibration: 0: no, 1: yes | Magnetometer calibration: 0: no, 1: yes | Ground pressure: 0: no, 1: yes | Radio calibration: 0: no, 1: yes | Empty | Empty | Empty | */
+    MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. | Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Reserved | Reserved | Empty | Empty | Empty | */
+    MAV_CMD_ENUM_END
+};
+
+/** @brief  Data stream IDs. A data stream is not a fixed set of messages, but rather a      recommendation to the autopilot software. Individual autopilots may or may not obey      the recommended messages.       */
+enum MAV_DATA_STREAM
+{
+    MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
+    MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
+    MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
+    MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
+    MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
+    MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
+    MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
+    MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
+    MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
+    MAV_DATA_STREAM_ENUM_END
+};
+
+/** @brief   The ROI (region of interest) for the vehicle. This can be                 be used by the vehicle for camera/vehicle attitude alignment (see                 MAV_CMD_NAV_ROI).              */
+enum MAV_ROI
+{
+    MAV_ROI_NONE=0, /* No region of interest. | */
+    MAV_ROI_WPNEXT=1, /* Point toward next waypoint. | */
+    MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */
+    MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
+    MAV_ROI_TARGET=4, /* Point toward of given id. | */
+    MAV_ROI_ENUM_END
+};
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_heartbeat.h"
+#include "./mavlink_msg_boot.h"
+#include "./mavlink_msg_system_time.h"
+#include "./mavlink_msg_ping.h"
+#include "./mavlink_msg_system_time_utc.h"
+#include "./mavlink_msg_change_operator_control.h"
+#include "./mavlink_msg_change_operator_control_ack.h"
+#include "./mavlink_msg_auth_key.h"
+#include "./mavlink_msg_action_ack.h"
+#include "./mavlink_msg_action.h"
+#include "./mavlink_msg_set_mode.h"
+#include "./mavlink_msg_set_nav_mode.h"
+#include "./mavlink_msg_param_request_read.h"
+#include "./mavlink_msg_param_request_list.h"
+#include "./mavlink_msg_param_value.h"
+#include "./mavlink_msg_param_set.h"
+#include "./mavlink_msg_gps_raw_int.h"
+#include "./mavlink_msg_scaled_imu.h"
+#include "./mavlink_msg_gps_status.h"
+#include "./mavlink_msg_raw_imu.h"
+#include "./mavlink_msg_raw_pressure.h"
+#include "./mavlink_msg_scaled_pressure.h"
+#include "./mavlink_msg_attitude.h"
+#include "./mavlink_msg_local_position.h"
+#include "./mavlink_msg_global_position.h"
+#include "./mavlink_msg_gps_raw.h"
+#include "./mavlink_msg_gps_raw_ugv.h"
+#include "./mavlink_msg_sys_status.h"
+#include "./mavlink_msg_rc_channels_raw.h"
+#include "./mavlink_msg_rc_channels_scaled.h"
+#include "./mavlink_msg_servo_output_raw.h"
+#include "./mavlink_msg_waypoint.h"
+#include "./mavlink_msg_waypoint_request.h"
+#include "./mavlink_msg_waypoint_set_current.h"
+#include "./mavlink_msg_waypoint_current.h"
+#include "./mavlink_msg_waypoint_request_list.h"
+#include "./mavlink_msg_waypoint_count.h"
+#include "./mavlink_msg_waypoint_clear_all.h"
+#include "./mavlink_msg_waypoint_reached.h"
+#include "./mavlink_msg_waypoint_ack.h"
+#include "./mavlink_msg_gps_set_global_origin.h"
+#include "./mavlink_msg_gps_local_origin_set.h"
+#include "./mavlink_msg_local_position_setpoint_set.h"
+#include "./mavlink_msg_local_position_setpoint.h"
+#include "./mavlink_msg_control_status.h"
+#include "./mavlink_msg_safety_set_allowed_area.h"
+#include "./mavlink_msg_safety_allowed_area.h"
+#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h"
+#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h"
+#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h"
+#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h"
+#include "./mavlink_msg_nav_controller_output.h"
+#include "./mavlink_msg_position_target.h"
+#include "./mavlink_msg_state_correction.h"
+#include "./mavlink_msg_set_altitude.h"
+#include "./mavlink_msg_request_data_stream.h"
+#include "./mavlink_msg_hil_state.h"
+#include "./mavlink_msg_hil_controls.h"
+#include "./mavlink_msg_manual_control.h"
+#include "./mavlink_msg_rc_channels_override.h"
+#include "./mavlink_msg_global_position_int.h"
+#include "./mavlink_msg_vfr_hud.h"
+#include "./mavlink_msg_command.h"
+#include "./mavlink_msg_command_ack.h"
+#include "./mavlink_msg_optical_flow.h"
+#include "./mavlink_msg_object_detection_event.h"
+#include "./mavlink_msg_debug_vect.h"
+#include "./mavlink_msg_named_value_float.h"
+#include "./mavlink_msg_named_value_int.h"
+#include "./mavlink_msg_statustext.h"
+#include "./mavlink_msg_debug.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Sunday, September 11 2011, 13:52 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "common.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_action.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,135 @@
+// MESSAGE ACTION PACKING
+
+#define MAVLINK_MSG_ID_ACTION 10
+
+typedef struct __mavlink_action_t 
+{
+	uint8_t target; ///< The system executing the action
+	uint8_t target_component; ///< The component executing the action
+	uint8_t action; ///< The action id
+
+} mavlink_action_t;
+
+
+
+/**
+ * @brief Pack a action 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 target The system executing the action
+ * @param target_component The component executing the action
+ * @param action The action id
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ACTION;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action
+	i += put_uint8_t_by_index(action, i, msg->payload); // The action id
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a action message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system executing the action
+ * @param target_component The component executing the action
+ * @param action The action id
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ACTION;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action
+	i += put_uint8_t_by_index(action, i, msg->payload); // The action id
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a action struct into a 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 action C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action)
+{
+	return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action);
+}
+
+/**
+ * @brief Send a action message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system executing the action
+ * @param target_component The component executing the action
+ * @param action The action id
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action)
+{
+	mavlink_message_t msg;
+	mavlink_msg_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, target_component, action);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ACTION UNPACKING
+
+/**
+ * @brief Get field target from action message
+ *
+ * @return The system executing the action
+ */
+static inline uint8_t mavlink_msg_action_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from action message
+ *
+ * @return The component executing the action
+ */
+static inline uint8_t mavlink_msg_action_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field action from action message
+ *
+ * @return The action id
+ */
+static inline uint8_t mavlink_msg_action_get_action(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a action message into a struct
+ *
+ * @param msg The message to decode
+ * @param action C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_action_decode(const mavlink_message_t* msg, mavlink_action_t* action)
+{
+	action->target = mavlink_msg_action_get_target(msg);
+	action->target_component = mavlink_msg_action_get_target_component(msg);
+	action->action = mavlink_msg_action_get_action(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_action_ack.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE ACTION_ACK PACKING
+
+#define MAVLINK_MSG_ID_ACTION_ACK 9
+
+typedef struct __mavlink_action_ack_t 
+{
+	uint8_t action; ///< The action id
+	uint8_t result; ///< 0: Action DENIED, 1: Action executed
+
+} mavlink_action_ack_t;
+
+
+
+/**
+ * @brief Pack a action_ack 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 action The action id
+ * @param result 0: Action DENIED, 1: Action executed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t action, uint8_t result)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
+
+	i += put_uint8_t_by_index(action, i, msg->payload); // The action id
+	i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a action_ack message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param action The action id
+ * @param result 0: Action DENIED, 1: Action executed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t action, uint8_t result)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
+
+	i += put_uint8_t_by_index(action, i, msg->payload); // The action id
+	i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a action_ack struct into a 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 action_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack)
+{
+	return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result);
+}
+
+/**
+ * @brief Send a action_ack message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param action The action id
+ * @param result 0: Action DENIED, 1: Action executed
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result)
+{
+	mavlink_message_t msg;
+	mavlink_msg_action_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, action, result);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ACTION_ACK UNPACKING
+
+/**
+ * @brief Get field action from action_ack message
+ *
+ * @return The action id
+ */
+static inline uint8_t mavlink_msg_action_ack_get_action(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field result from action_ack message
+ *
+ * @return 0: Action DENIED, 1: Action executed
+ */
+static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a action_ack message into a struct
+ *
+ * @param msg The message to decode
+ * @param action_ack C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack)
+{
+	action_ack->action = mavlink_msg_action_ack_get_action(msg);
+	action_ack->result = mavlink_msg_action_ack_get_result(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_attitude.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE ATTITUDE PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE 30
+
+typedef struct __mavlink_attitude_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    float roll; ///< Roll angle (rad)
+    float pitch; ///< Pitch angle (rad)
+    float yaw; ///< Yaw angle (rad)
+    float rollspeed; ///< Roll angular speed (rad/s)
+    float pitchspeed; ///< Pitch angular speed (rad/s)
+    float yawspeed; ///< Yaw angular speed (rad/s)
+
+} mavlink_attitude_t;
+
+
+
+/**
+ * @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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @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, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+    i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+    i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+    i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+    i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+    i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @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, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+    i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+    i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+    i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+    i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+    i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a attitude struct into a 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 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->usec, 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @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, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+    mavlink_message_t msg;
+    mavlink_msg_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ATTITUDE UNPACKING
+
+/**
+ * @brief Get field usec from attitude message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_attitude_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll from attitude message
+ *
+ * @return Roll angle (rad)
+ */
+static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from attitude message
+ *
+ * @return Pitch angle (rad)
+ */
+static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from attitude message
+ *
+ * @return Yaw angle (rad)
+ */
+static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @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)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @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)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @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)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @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)
+{
+    attitude->usec = mavlink_msg_attitude_get_usec(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);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_auth_key.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,104 @@
+// MESSAGE AUTH_KEY PACKING
+
+#define MAVLINK_MSG_ID_AUTH_KEY 7
+
+typedef struct __mavlink_auth_key_t 
+{
+	char key[32]; ///< key
+
+} mavlink_auth_key_t;
+
+#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
+
+
+/**
+ * @brief Pack a auth_key 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 key key
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* key)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
+
+	i += put_array_by_index((const int8_t*)key, sizeof(char)*32, i, msg->payload); // key
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a auth_key message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param key key
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* key)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
+
+	i += put_array_by_index((const int8_t*)key, sizeof(char)*32, i, msg->payload); // key
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a auth_key struct into a 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 auth_key C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
+{
+	return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
+}
+
+/**
+ * @brief Send a auth_key message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param key key
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char* key)
+{
+	mavlink_message_t msg;
+	mavlink_msg_auth_key_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, key);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE AUTH_KEY UNPACKING
+
+/**
+ * @brief Get field key from auth_key message
+ *
+ * @return key
+ */
+static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload, sizeof(char)*32);
+	return sizeof(char)*32;
+}
+
+/**
+ * @brief Decode a auth_key message into a struct
+ *
+ * @param msg The message to decode
+ * @param auth_key C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
+{
+	mavlink_msg_auth_key_get_key(msg, auth_key->key);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_boot.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,106 @@
+// MESSAGE BOOT PACKING
+
+#define MAVLINK_MSG_ID_BOOT 1
+
+typedef struct __mavlink_boot_t 
+{
+	uint32_t version; ///< The onboard software version
+
+} mavlink_boot_t;
+
+
+
+/**
+ * @brief Pack a boot 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 version The onboard software version
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t version)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_BOOT;
+
+	i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a boot message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param version The onboard software version
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t version)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_BOOT;
+
+	i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a boot struct into a 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 boot C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot)
+{
+	return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
+}
+
+/**
+ * @brief Send a boot message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param version The onboard software version
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
+{
+	mavlink_message_t msg;
+	mavlink_msg_boot_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, version);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE BOOT UNPACKING
+
+/**
+ * @brief Get field version from boot message
+ *
+ * @return The onboard software version
+ */
+static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Decode a boot message into a struct
+ *
+ * @param msg The message to decode
+ * @param boot C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot)
+{
+	boot->version = mavlink_msg_boot_get_version(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_change_operator_control.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,155 @@
+// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
+
+typedef struct __mavlink_change_operator_control_t 
+{
+	uint8_t target_system; ///< System the GCS requests control for
+	uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
+	uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+	char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+
+} mavlink_change_operator_control_t;
+
+#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
+
+
+/**
+ * @brief Pack a change_operator_control 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 target_system System the GCS requests control for
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
+	i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
+	i += put_uint8_t_by_index(version, i, msg->payload); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+	i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a change_operator_control message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System the GCS requests control for
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
+	i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
+	i += put_uint8_t_by_index(version, i, msg->payload); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+	i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a change_operator_control struct into a 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 change_operator_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
+{
+	return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
+}
+
+/**
+ * @brief Send a change_operator_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System the GCS requests control for
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
+{
+	mavlink_message_t msg;
+	mavlink_msg_change_operator_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, control_request, version, passkey);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
+
+/**
+ * @brief Get field target_system from change_operator_control message
+ *
+ * @return System the GCS requests control for
+ */
+static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field control_request from change_operator_control message
+ *
+ * @return 0: request control of this MAV, 1: Release control of this MAV
+ */
+static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field version from change_operator_control message
+ *
+ * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ */
+static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field passkey from change_operator_control message
+ *
+ * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
+ */
+static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t), sizeof(char)*25);
+	return sizeof(char)*25;
+}
+
+/**
+ * @brief Decode a change_operator_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param change_operator_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
+{
+	change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
+	change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
+	change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
+	mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_change_operator_control_ack.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,135 @@
+// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING
+
+#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
+
+typedef struct __mavlink_change_operator_control_ack_t 
+{
+	uint8_t gcs_system_id; ///< ID of the GCS this message 
+	uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
+	uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+
+} mavlink_change_operator_control_ack_t;
+
+
+
+/**
+ * @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message 
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
+
+	i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message 
+	i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
+	i += put_uint8_t_by_index(ack, i, msg->payload); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a change_operator_control_ack message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param gcs_system_id ID of the GCS this message 
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
+
+	i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message 
+	i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
+	i += put_uint8_t_by_index(ack, i, msg->payload); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a change_operator_control_ack struct into a 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 change_operator_control_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
+{
+	return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
+}
+
+/**
+ * @brief Send a change_operator_control_ack message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param gcs_system_id ID of the GCS this message 
+ * @param control_request 0: request control of this MAV, 1: Release control of this MAV
+ * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
+{
+	mavlink_message_t msg;
+	mavlink_msg_change_operator_control_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, gcs_system_id, control_request, ack);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING
+
+/**
+ * @brief Get field gcs_system_id from change_operator_control_ack message
+ *
+ * @return ID of the GCS this message 
+ */
+static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field control_request from change_operator_control_ack message
+ *
+ * @return 0: request control of this MAV, 1: Release control of this MAV
+ */
+static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field ack from change_operator_control_ack message
+ *
+ * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
+ */
+static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a change_operator_control_ack message into a struct
+ *
+ * @param msg The message to decode
+ * @param change_operator_control_ack C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack)
+{
+	change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg);
+	change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg);
+	change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_command.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,240 @@
+// MESSAGE COMMAND PACKING
+
+#define MAVLINK_MSG_ID_COMMAND 75
+
+typedef struct __mavlink_command_t 
+{
+	uint8_t target_system; ///< System which should execute the command
+	uint8_t target_component; ///< Component which should execute the command, 0 for all components
+	uint8_t command; ///< Command ID, as defined by MAV_CMD enum.
+	uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+	float param1; ///< Parameter 1, as defined by MAV_CMD enum.
+	float param2; ///< Parameter 2, as defined by MAV_CMD enum.
+	float param3; ///< Parameter 3, as defined by MAV_CMD enum.
+	float param4; ///< Parameter 4, as defined by MAV_CMD enum.
+
+} mavlink_command_t;
+
+
+
+/**
+ * @brief Pack a command 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 target_system System which should execute the command
+ * @param target_component Component which should execute the command, 0 for all components
+ * @param command Command ID, as defined by MAV_CMD enum.
+ * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+ * @param param1 Parameter 1, as defined by MAV_CMD enum.
+ * @param param2 Parameter 2, as defined by MAV_CMD enum.
+ * @param param3 Parameter 3, as defined by MAV_CMD enum.
+ * @param param4 Parameter 4, as defined by MAV_CMD enum.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_COMMAND;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components
+	i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum.
+	i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+	i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum.
+	i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum.
+	i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum.
+	i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum.
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a command message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System which should execute the command
+ * @param target_component Component which should execute the command, 0 for all components
+ * @param command Command ID, as defined by MAV_CMD enum.
+ * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+ * @param param1 Parameter 1, as defined by MAV_CMD enum.
+ * @param param2 Parameter 2, as defined by MAV_CMD enum.
+ * @param param3 Parameter 3, as defined by MAV_CMD enum.
+ * @param param4 Parameter 4, as defined by MAV_CMD enum.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_COMMAND;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components
+	i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum.
+	i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+	i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum.
+	i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum.
+	i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum.
+	i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum.
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a command struct into a 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 command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command)
+{
+	return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4);
+}
+
+/**
+ * @brief Send a command message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System which should execute the command
+ * @param target_component Component which should execute the command, 0 for all components
+ * @param command Command ID, as defined by MAV_CMD enum.
+ * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+ * @param param1 Parameter 1, as defined by MAV_CMD enum.
+ * @param param2 Parameter 2, as defined by MAV_CMD enum.
+ * @param param3 Parameter 3, as defined by MAV_CMD enum.
+ * @param param4 Parameter 4, as defined by MAV_CMD enum.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
+{
+	mavlink_message_t msg;
+	mavlink_msg_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, command, confirmation, param1, param2, param3, param4);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE COMMAND UNPACKING
+
+/**
+ * @brief Get field target_system from command message
+ *
+ * @return System which should execute the command
+ */
+static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from command message
+ *
+ * @return Component which should execute the command, 0 for all components
+ */
+static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field command from command message
+ *
+ * @return Command ID, as defined by MAV_CMD enum.
+ */
+static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field confirmation from command message
+ *
+ * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+ */
+static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field param1 from command message
+ *
+ * @return Parameter 1, as defined by MAV_CMD enum.
+ */
+static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param2 from command message
+ *
+ * @return Parameter 2, as defined by MAV_CMD enum.
+ */
+static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param3 from command message
+ *
+ * @return Parameter 3, as defined by MAV_CMD enum.
+ */
+static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param4 from command message
+ *
+ * @return Parameter 4, as defined by MAV_CMD enum.
+ */
+static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a command message into a struct
+ *
+ * @param msg The message to decode
+ * @param command C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command)
+{
+	command->target_system = mavlink_msg_command_get_target_system(msg);
+	command->target_component = mavlink_msg_command_get_target_component(msg);
+	command->command = mavlink_msg_command_get_command(msg);
+	command->confirmation = mavlink_msg_command_get_confirmation(msg);
+	command->param1 = mavlink_msg_command_get_param1(msg);
+	command->param2 = mavlink_msg_command_get_param2(msg);
+	command->param3 = mavlink_msg_command_get_param3(msg);
+	command->param4 = mavlink_msg_command_get_param4(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_command_ack.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,128 @@
+// MESSAGE COMMAND_ACK PACKING
+
+#define MAVLINK_MSG_ID_COMMAND_ACK 76
+
+typedef struct __mavlink_command_ack_t 
+{
+	float command; ///< Current airspeed in m/s
+	float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+
+} mavlink_command_ack_t;
+
+
+
+/**
+ * @brief Pack a command_ack 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 command Current airspeed in m/s
+ * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float command, float result)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
+
+	i += put_float_by_index(command, i, msg->payload); // Current airspeed in m/s
+	i += put_float_by_index(result, i, msg->payload); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a command_ack message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param command Current airspeed in m/s
+ * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float command, float result)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
+
+	i += put_float_by_index(command, i, msg->payload); // Current airspeed in m/s
+	i += put_float_by_index(result, i, msg->payload); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a command_ack struct into a 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 command_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
+{
+	return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
+}
+
+/**
+ * @brief Send a command_ack message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param command Current airspeed in m/s
+ * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result)
+{
+	mavlink_message_t msg;
+	mavlink_msg_command_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, command, result);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE COMMAND_ACK UNPACKING
+
+/**
+ * @brief Get field command from command_ack message
+ *
+ * @return Current airspeed in m/s
+ */
+static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field result from command_ack message
+ *
+ * @return 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+ */
+static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a command_ack message into a struct
+ *
+ * @param msg The message to decode
+ * @param command_ack C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
+{
+	command_ack->command = mavlink_msg_command_ack_get_command(msg);
+	command_ack->result = mavlink_msg_command_ack_get_result(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_control_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,220 @@
+// MESSAGE CONTROL_STATUS PACKING
+
+#define MAVLINK_MSG_ID_CONTROL_STATUS 52
+
+typedef struct __mavlink_control_status_t 
+{
+	uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+	uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+	uint8_t gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+	uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent
+	uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled
+	uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled
+	uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled
+	uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled
+
+} mavlink_control_status_t;
+
+
+
+/**
+ * @brief Pack a control_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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+ * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+ * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+ * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
+ * @param control_att 0: Attitude control disabled, 1: enabled
+ * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
+ * @param control_pos_z 0: Z position control disabled, 1: enabled
+ * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
+
+	i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+	i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+	i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+	i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent
+	i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a control_status message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+ * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+ * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+ * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
+ * @param control_att 0: Attitude control disabled, 1: enabled
+ * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
+ * @param control_pos_z 0: Z position control disabled, 1: enabled
+ * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
+
+	i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+	i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+	i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+	i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent
+	i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
+	i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a control_status struct into a 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 control_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status)
+{
+	return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->ahrs_health, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw);
+}
+
+/**
+ * @brief Send a control_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+ * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+ * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+ * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
+ * @param control_att 0: Attitude control disabled, 1: enabled
+ * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
+ * @param control_pos_z 0: Z position control disabled, 1: enabled
+ * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_control_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE CONTROL_STATUS UNPACKING
+
+/**
+ * @brief Get field position_fix from control_status message
+ *
+ * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
+ */
+static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field vision_fix from control_status message
+ *
+ * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
+ */
+static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field gps_fix from control_status message
+ *
+ * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
+ */
+static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field ahrs_health from control_status message
+ *
+ * @return Attitude estimation health: 0: poor, 255: excellent
+ */
+static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field control_att from control_status message
+ *
+ * @return 0: Attitude control disabled, 1: enabled
+ */
+static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field control_pos_xy from control_status message
+ *
+ * @return 0: X, Y position control disabled, 1: enabled
+ */
+static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field control_pos_z from control_status message
+ *
+ * @return 0: Z position control disabled, 1: enabled
+ */
+static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field control_pos_yaw from control_status message
+ *
+ * @return 0: Yaw angle control disabled, 1: enabled
+ */
+static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a control_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param control_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status)
+{
+	control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg);
+	control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg);
+	control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg);
+	control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg);
+	control_status->control_att = mavlink_msg_control_status_get_control_att(msg);
+	control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg);
+	control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg);
+	control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_debug.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,123 @@
+// MESSAGE DEBUG PACKING
+
+#define MAVLINK_MSG_ID_DEBUG 255
+
+typedef struct __mavlink_debug_t 
+{
+	uint8_t ind; ///< index of debug variable
+	float value; ///< DEBUG value
+
+} mavlink_debug_t;
+
+
+
+/**
+ * @brief Pack a debug 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 ind index of debug variable
+ * @param value DEBUG value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t ind, float value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DEBUG;
+
+	i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
+	i += put_float_by_index(value, i, msg->payload); // DEBUG value
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a debug message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param ind index of debug variable
+ * @param value DEBUG value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DEBUG;
+
+	i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
+	i += put_float_by_index(value, i, msg->payload); // DEBUG value
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a debug struct into a 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 debug C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
+{
+	return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
+}
+
+/**
+ * @brief Send a debug message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param ind index of debug variable
+ * @param value DEBUG value
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
+{
+	mavlink_message_t msg;
+	mavlink_msg_debug_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, ind, value);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE DEBUG UNPACKING
+
+/**
+ * @brief Get field ind from debug message
+ *
+ * @return index of debug variable
+ */
+static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field value from debug message
+ *
+ * @return DEBUG value
+ */
+static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a debug message into a struct
+ *
+ * @param msg The message to decode
+ * @param debug C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
+{
+	debug->ind = mavlink_msg_debug_get_ind(msg);
+	debug->value = mavlink_msg_debug_get_value(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_debug_vect.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,196 @@
+// MESSAGE DEBUG_VECT PACKING
+
+#define MAVLINK_MSG_ID_DEBUG_VECT 251
+
+typedef struct __mavlink_debug_vect_t 
+{
+	char name[10]; ///< Name
+	uint64_t usec; ///< Timestamp
+	float x; ///< x
+	float y; ///< y
+	float z; ///< z
+
+} mavlink_debug_vect_t;
+
+#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
+
+
+/**
+ * @brief Pack a debug_vect 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 name Name
+ * @param usec Timestamp
+ * @param x x
+ * @param y y
+ * @param z z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
+	i += put_float_by_index(x, i, msg->payload); // x
+	i += put_float_by_index(y, i, msg->payload); // y
+	i += put_float_by_index(z, i, msg->payload); // z
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a debug_vect message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param name Name
+ * @param usec Timestamp
+ * @param x x
+ * @param y y
+ * @param z z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
+	i += put_float_by_index(x, i, msg->payload); // x
+	i += put_float_by_index(y, i, msg->payload); // y
+	i += put_float_by_index(z, i, msg->payload); // z
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a debug_vect struct into a 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 debug_vect C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
+{
+	return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
+}
+
+/**
+ * @brief Send a debug_vect message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param name Name
+ * @param usec Timestamp
+ * @param x x
+ * @param y y
+ * @param z z
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char* name, uint64_t usec, float x, float y, float z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_debug_vect_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, usec, x, y, z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE DEBUG_VECT UNPACKING
+
+/**
+ * @brief Get field name from debug_vect message
+ *
+ * @return Name
+ */
+static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload, sizeof(char)*10);
+	return sizeof(char)*10;
+}
+
+/**
+ * @brief Get field usec from debug_vect message
+ *
+ * @return Timestamp
+ */
+static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload+sizeof(char)*10)[0];
+	r.b[6] = (msg->payload+sizeof(char)*10)[1];
+	r.b[5] = (msg->payload+sizeof(char)*10)[2];
+	r.b[4] = (msg->payload+sizeof(char)*10)[3];
+	r.b[3] = (msg->payload+sizeof(char)*10)[4];
+	r.b[2] = (msg->payload+sizeof(char)*10)[5];
+	r.b[1] = (msg->payload+sizeof(char)*10)[6];
+	r.b[0] = (msg->payload+sizeof(char)*10)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from debug_vect message
+ *
+ * @return x
+ */
+static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from debug_vect message
+ *
+ * @return y
+ */
+static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from debug_vect message
+ *
+ * @return z
+ */
+static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a debug_vect message into a struct
+ *
+ * @param msg The message to decode
+ * @param debug_vect C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
+{
+	mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
+	debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
+	debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
+	debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
+	debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_full_state.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,428 @@
+// MESSAGE FULL_STATE PACKING
+
+#define MAVLINK_MSG_ID_FULL_STATE 67
+
+typedef struct __mavlink_full_state_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	float roll; ///< Roll angle (rad)
+	float pitch; ///< Pitch angle (rad)
+	float yaw; ///< Yaw angle (rad)
+	float rollspeed; ///< Roll angular speed (rad/s)
+	float pitchspeed; ///< Pitch angular speed (rad/s)
+	float yawspeed; ///< Yaw angular speed (rad/s)
+	int32_t lat; ///< Latitude, expressed as * 1E7
+	int32_t lon; ///< Longitude, expressed as * 1E7
+	int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
+	int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
+	int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
+	int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
+	int16_t xacc; ///< X acceleration (mg)
+	int16_t yacc; ///< Y acceleration (mg)
+	int16_t zacc; ///< Z acceleration (mg)
+
+} mavlink_full_state_t;
+
+
+
+/**
+ * @brief Pack a full_state 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_full_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_FULL_STATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+	i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+	i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+	i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+	i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+	i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+	i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+	i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a full_state message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_full_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_FULL_STATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+	i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+	i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+	i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+	i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+	i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+	i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+	i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a full_state struct into a 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 full_state C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_full_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_full_state_t* full_state)
+{
+	return mavlink_msg_full_state_pack(system_id, component_id, msg, full_state->usec, full_state->roll, full_state->pitch, full_state->yaw, full_state->rollspeed, full_state->pitchspeed, full_state->yawspeed, full_state->lat, full_state->lon, full_state->alt, full_state->vx, full_state->vy, full_state->vz, full_state->xacc, full_state->yacc, full_state->zacc);
+}
+
+/**
+ * @brief Send a full_state message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_full_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	mavlink_message_t msg;
+	mavlink_msg_full_state_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE FULL_STATE UNPACKING
+
+/**
+ * @brief Get field usec from full_state message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_full_state_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll from full_state message
+ *
+ * @return Roll angle (rad)
+ */
+static inline float mavlink_msg_full_state_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from full_state message
+ *
+ * @return Pitch angle (rad)
+ */
+static inline float mavlink_msg_full_state_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from full_state message
+ *
+ * @return Yaw angle (rad)
+ */
+static inline float mavlink_msg_full_state_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field rollspeed from full_state message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_full_state_get_rollspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitchspeed from full_state message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_full_state_get_pitchspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yawspeed from full_state message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_full_state_get_yawspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lat from full_state message
+ *
+ * @return Latitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_full_state_get_lat(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field lon from full_state message
+ *
+ * @return Longitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_full_state_get_lon(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field alt from full_state message
+ *
+ * @return Altitude in meters, expressed as * 1000 (millimeters)
+ */
+static inline int32_t mavlink_msg_full_state_get_alt(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field vx from full_state message
+ *
+ * @return Ground X Speed (Latitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_full_state_get_vx(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vy from full_state message
+ *
+ * @return Ground Y Speed (Longitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_full_state_get_vy(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vz from full_state message
+ *
+ * @return Ground Z Speed (Altitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_full_state_get_vz(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field xacc from full_state message
+ *
+ * @return X acceleration (mg)
+ */
+static inline int16_t mavlink_msg_full_state_get_xacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field yacc from full_state message
+ *
+ * @return Y acceleration (mg)
+ */
+static inline int16_t mavlink_msg_full_state_get_yacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field zacc from full_state message
+ *
+ * @return Z acceleration (mg)
+ */
+static inline int16_t mavlink_msg_full_state_get_zacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a full_state message into a struct
+ *
+ * @param msg The message to decode
+ * @param full_state C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_full_state_decode(const mavlink_message_t* msg, mavlink_full_state_t* full_state)
+{
+	full_state->usec = mavlink_msg_full_state_get_usec(msg);
+	full_state->roll = mavlink_msg_full_state_get_roll(msg);
+	full_state->pitch = mavlink_msg_full_state_get_pitch(msg);
+	full_state->yaw = mavlink_msg_full_state_get_yaw(msg);
+	full_state->rollspeed = mavlink_msg_full_state_get_rollspeed(msg);
+	full_state->pitchspeed = mavlink_msg_full_state_get_pitchspeed(msg);
+	full_state->yawspeed = mavlink_msg_full_state_get_yawspeed(msg);
+	full_state->lat = mavlink_msg_full_state_get_lat(msg);
+	full_state->lon = mavlink_msg_full_state_get_lon(msg);
+	full_state->alt = mavlink_msg_full_state_get_alt(msg);
+	full_state->vx = mavlink_msg_full_state_get_vx(msg);
+	full_state->vy = mavlink_msg_full_state_get_vy(msg);
+	full_state->vz = mavlink_msg_full_state_get_vz(msg);
+	full_state->xacc = mavlink_msg_full_state_get_xacc(msg);
+	full_state->yacc = mavlink_msg_full_state_get_yacc(msg);
+	full_state->zacc = mavlink_msg_full_state_get_zacc(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_global_position.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE GLOBAL_POSITION PACKING
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
+
+typedef struct __mavlink_global_position_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since unix epoch)
+    float lat; ///< Latitude, in degrees
+    float lon; ///< Longitude, in degrees
+    float alt; ///< Absolute altitude, in meters
+    float vx; ///< X Speed (in Latitude direction, positive: going north)
+    float vy; ///< Y Speed (in Longitude direction, positive: going east)
+    float vz; ///< Z Speed (in Altitude direction, positive: going up)
+
+} mavlink_global_position_t;
+
+
+
+/**
+ * @brief Pack a global_position 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 usec Timestamp (microseconds since unix epoch)
+ * @param lat Latitude, in degrees
+ * @param lon Longitude, in degrees
+ * @param alt Absolute altitude, in meters
+ * @param vx X Speed (in Latitude direction, positive: going north)
+ * @param vy Y Speed (in Longitude direction, positive: going east)
+ * @param vz Z Speed (in Altitude direction, positive: going up)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
+    i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees
+    i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees
+    i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters
+    i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north)
+    i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east)
+    i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up)
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a global_position message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since unix epoch)
+ * @param lat Latitude, in degrees
+ * @param lon Longitude, in degrees
+ * @param alt Absolute altitude, in meters
+ * @param vx X Speed (in Latitude direction, positive: going north)
+ * @param vy Y Speed (in Longitude direction, positive: going east)
+ * @param vz Z Speed (in Altitude direction, positive: going up)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
+    i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees
+    i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees
+    i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters
+    i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north)
+    i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east)
+    i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up)
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a global_position struct into a 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 global_position C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
+{
+    return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
+}
+
+/**
+ * @brief Send a global_position message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since unix epoch)
+ * @param lat Latitude, in degrees
+ * @param lon Longitude, in degrees
+ * @param alt Absolute altitude, in meters
+ * @param vx X Speed (in Latitude direction, positive: going north)
+ * @param vy Y Speed (in Longitude direction, positive: going east)
+ * @param vz Z Speed (in Altitude direction, positive: going up)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
+{
+    mavlink_message_t msg;
+    mavlink_msg_global_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, lat, lon, alt, vx, vy, vz);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GLOBAL_POSITION UNPACKING
+
+/**
+ * @brief Get field usec from global_position message
+ *
+ * @return Timestamp (microseconds since unix epoch)
+ */
+static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field lat from global_position message
+ *
+ * @return Latitude, in degrees
+ */
+static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field lon from global_position message
+ *
+ * @return Longitude, in degrees
+ */
+static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field alt from global_position message
+ *
+ * @return Absolute altitude, in meters
+ */
+static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vx from global_position message
+ *
+ * @return X Speed (in Latitude direction, positive: going north)
+ */
+static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vy from global_position message
+ *
+ * @return Y Speed (in Longitude direction, positive: going east)
+ */
+static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vz from global_position message
+ *
+ * @return Z Speed (in Altitude direction, positive: going up)
+ */
+static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a global_position message into a struct
+ *
+ * @param msg The message to decode
+ * @param global_position C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
+{
+    global_position->usec = mavlink_msg_global_position_get_usec(msg);
+    global_position->lat = mavlink_msg_global_position_get_lat(msg);
+    global_position->lon = mavlink_msg_global_position_get_lon(msg);
+    global_position->alt = mavlink_msg_global_position_get_alt(msg);
+    global_position->vx = mavlink_msg_global_position_get_vx(msg);
+    global_position->vy = mavlink_msg_global_position_get_vy(msg);
+    global_position->vz = mavlink_msg_global_position_get_vz(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_global_position_int.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,210 @@
+// MESSAGE GLOBAL_POSITION_INT PACKING
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
+
+typedef struct __mavlink_global_position_int_t 
+{
+    int32_t lat; ///< Latitude, expressed as * 1E7
+    int32_t lon; ///< Longitude, expressed as * 1E7
+    int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
+    int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
+    int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
+    int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
+
+} mavlink_global_position_int_t;
+
+
+
+/**
+ * @brief Pack a global_position_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 lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
+
+    i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+    i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+    i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+    i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+    i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+    i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a global_position_int message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
+
+    i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+    i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+    i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+    i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+    i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+    i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a global_position_int struct into a 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 global_position_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
+{
+    return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
+}
+
+/**
+ * @brief Send a global_position_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
+{
+    mavlink_message_t msg;
+    mavlink_msg_global_position_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, lat, lon, alt, vx, vy, vz);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GLOBAL_POSITION_INT UNPACKING
+
+/**
+ * @brief Get field lat from global_position_int message
+ *
+ * @return Latitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload)[0];
+    r.b[2] = (msg->payload)[1];
+    r.b[1] = (msg->payload)[2];
+    r.b[0] = (msg->payload)[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field lon from global_position_int message
+ *
+ * @return Longitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(int32_t))[0];
+    r.b[2] = (msg->payload+sizeof(int32_t))[1];
+    r.b[1] = (msg->payload+sizeof(int32_t))[2];
+    r.b[0] = (msg->payload+sizeof(int32_t))[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field alt from global_position_int message
+ *
+ * @return Altitude in meters, expressed as * 1000 (millimeters)
+ */
+static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
+    r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
+    r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
+    r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field vx from global_position_int message
+ *
+ * @return Ground X Speed (Latitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+    r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vy from global_position_int message
+ *
+ * @return Ground Y Speed (Longitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vz from global_position_int message
+ *
+ * @return Ground Z Speed (Altitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a global_position_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param global_position_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
+{
+    global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
+    global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
+    global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
+    global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
+    global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
+    global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_local_origin_set.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,150 @@
+// MESSAGE GPS_LOCAL_ORIGIN_SET PACKING
+
+#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 49
+
+typedef struct __mavlink_gps_local_origin_set_t 
+{
+	int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7
+	int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7
+	int32_t altitude; ///< Altitude(WGS84), expressed as * 1000
+
+} mavlink_gps_local_origin_set_t;
+
+
+
+/**
+ * @brief Pack a gps_local_origin_set 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 latitude Latitude (WGS84), expressed as * 1E7
+ * @param longitude Longitude (WGS84), expressed as * 1E7
+ * @param altitude Altitude(WGS84), expressed as * 1000
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
+
+	i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7
+	i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7
+	i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_local_origin_set message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param latitude Latitude (WGS84), expressed as * 1E7
+ * @param longitude Longitude (WGS84), expressed as * 1E7
+ * @param altitude Altitude(WGS84), expressed as * 1000
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
+
+	i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7
+	i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7
+	i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_local_origin_set struct into a 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 gps_local_origin_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_local_origin_set_t* gps_local_origin_set)
+{
+	return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude);
+}
+
+/**
+ * @brief Send a gps_local_origin_set message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param latitude Latitude (WGS84), expressed as * 1E7
+ * @param longitude Longitude (WGS84), expressed as * 1E7
+ * @param altitude Altitude(WGS84), expressed as * 1000
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	mavlink_message_t msg;
+	mavlink_msg_gps_local_origin_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, latitude, longitude, altitude);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_LOCAL_ORIGIN_SET UNPACKING
+
+/**
+ * @brief Get field latitude from gps_local_origin_set message
+ *
+ * @return Latitude (WGS84), expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_gps_local_origin_set_get_latitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field longitude from gps_local_origin_set message
+ *
+ * @return Longitude (WGS84), expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field altitude from gps_local_origin_set message
+ *
+ * @return Altitude(WGS84), expressed as * 1000
+ */
+static inline int32_t mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Decode a gps_local_origin_set message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_local_origin_set C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_local_origin_set_decode(const mavlink_message_t* msg, mavlink_gps_local_origin_set_t* gps_local_origin_set)
+{
+	gps_local_origin_set->latitude = mavlink_msg_gps_local_origin_set_get_latitude(msg);
+	gps_local_origin_set->longitude = mavlink_msg_gps_local_origin_set_get_longitude(msg);
+	gps_local_origin_set->altitude = mavlink_msg_gps_local_origin_set_get_altitude(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,281 @@
+// MESSAGE GPS_RAW PACKING
+
+#define MAVLINK_MSG_ID_GPS_RAW 32
+
+typedef struct __mavlink_gps_raw_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    float lat; ///< Latitude in degrees
+    float lon; ///< Longitude in degrees
+    float alt; ///< Altitude in meters
+    float eph; ///< GPS HDOP
+    float epv; ///< GPS VDOP
+    float v; ///< GPS ground speed
+    float hdg; ///< Compass heading in degrees, 0..360 degrees
+
+} mavlink_gps_raw_t;
+
+
+
+/**
+ * @brief Pack a gps_raw 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param alt Altitude in meters
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
+    i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
+    i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_raw message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param alt Altitude in meters
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
+    i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
+    i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_raw struct into a 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 gps_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
+{
+    return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
+}
+
+/**
+ * @brief Send a gps_raw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param alt Altitude in meters
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
+{
+    mavlink_message_t msg;
+    mavlink_msg_gps_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_RAW UNPACKING
+
+/**
+ * @brief Get field usec from gps_raw message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field fix_type from gps_raw message
+ *
+ * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ */
+static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
+}
+
+/**
+ * @brief Get field lat from gps_raw message
+ *
+ * @return Latitude in degrees
+ */
+static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field lon from gps_raw message
+ *
+ * @return Longitude in degrees
+ */
+static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field alt from gps_raw message
+ *
+ * @return Altitude in meters
+ */
+static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field eph from gps_raw message
+ *
+ * @return GPS HDOP
+ */
+static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field epv from gps_raw message
+ *
+ * @return GPS VDOP
+ */
+static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field v from gps_raw message
+ *
+ * @return GPS ground speed
+ */
+static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field hdg from gps_raw message
+ *
+ * @return Compass heading in degrees, 0..360 degrees
+ */
+static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a gps_raw message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_raw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
+{
+    gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);
+    gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg);
+    gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg);
+    gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg);
+    gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg);
+    gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg);
+    gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg);
+    gps_raw->v = mavlink_msg_gps_raw_get_v(msg);
+    gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw_int.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,281 @@
+// MESSAGE GPS_RAW_INT PACKING
+
+#define MAVLINK_MSG_ID_GPS_RAW_INT 25
+
+typedef struct __mavlink_gps_raw_int_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    int32_t lat; ///< Latitude in 1E7 degrees
+    int32_t lon; ///< Longitude in 1E7 degrees
+    int32_t alt; ///< Altitude in 1E3 meters (millimeters)
+    float eph; ///< GPS HDOP
+    float epv; ///< GPS VDOP
+    float v; ///< GPS ground speed (m/s)
+    float hdg; ///< Compass heading in degrees, 0..360 degrees
+
+} mavlink_gps_raw_int_t;
+
+
+
+/**
+ * @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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in 1E7 degrees
+ * @param lon Longitude in 1E7 degrees
+ * @param alt Altitude in 1E3 meters (millimeters)
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed (m/s)
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @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 usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
+    i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
+    i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s)
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in 1E7 degrees
+ * @param lon Longitude in 1E7 degrees
+ * @param alt Altitude in 1E3 meters (millimeters)
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed (m/s)
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @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 usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
+    i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
+    i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s)
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_raw_int struct into a 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 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->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->v, gps_raw_int->hdg);
+}
+
+/**
+ * @brief Send a gps_raw_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in 1E7 degrees
+ * @param lon Longitude in 1E7 degrees
+ * @param alt Altitude in 1E3 meters (millimeters)
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed (m/s)
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
+{
+    mavlink_message_t msg;
+    mavlink_msg_gps_raw_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_RAW_INT UNPACKING
+
+/**
+ * @brief Get field 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_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field fix_type from gps_raw_int message
+ *
+ * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ */
+static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
+}
+
+/**
+ * @brief Get field lat from gps_raw_int message
+ *
+ * @return Latitude in 1E7 degrees
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field lon from gps_raw_int message
+ *
+ * @return Longitude in 1E7 degrees
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field alt from gps_raw_int message
+ *
+ * @return Altitude in 1E3 meters (millimeters)
+ */
+static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3];
+    return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field eph from gps_raw_int message
+ *
+ * @return GPS HDOP
+ */
+static inline float mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field epv from gps_raw_int message
+ *
+ * @return GPS VDOP
+ */
+static inline float mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field v from gps_raw_int message
+ *
+ * @return GPS ground speed (m/s)
+ */
+static inline float mavlink_msg_gps_raw_int_get_v(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field hdg from gps_raw_int message
+ *
+ * @return Compass heading in degrees, 0..360 degrees
+ */
+static inline float mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @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)
+{
+    gps_raw_int->usec = mavlink_msg_gps_raw_int_get_usec(msg);
+    gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(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->v = mavlink_msg_gps_raw_int_get_v(msg);
+    gps_raw_int->hdg = mavlink_msg_gps_raw_int_get_hdg(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_raw_ugv.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,266 @@
+// MESSAGE GPS_RAW_UGV PACKING
+
+#define MAVLINK_MSG_ID_GPS_RAW_UGV 86
+
+typedef struct __mavlink_gps_raw_ugv_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    double lat; ///< Latitude in 1E15 degrees
+    double lon; ///< Longitude in 1E15 degrees
+    float eph; ///< GPS HDOP
+    float epv; ///< GPS VDOP
+    float v; ///< GPS ground speed
+    float hdg; ///< Compass heading in degrees, 0..360 degrees
+
+} mavlink_gps_raw_ugv_t;
+
+
+/**
+ * @brief Pack a gps_raw 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_ugv_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees
+    i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_raw message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_raw_ugv_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+    i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees
+    i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees
+    i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
+    i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
+    i += put_float_by_index(v, i, msg->payload); // GPS ground speed
+    i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_raw struct into a 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 gps_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_raw_ugv_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_ugv_t* gps_raw)
+{
+    return mavlink_msg_gps_raw_ugv_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
+}
+
+/**
+ * @brief Send a gps_raw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ * @param lat Latitude in degrees
+ * @param lon Longitude in degrees
+ * @param eph GPS HDOP
+ * @param epv GPS VDOP
+ * @param v GPS ground speed
+ * @param hdg Compass heading in degrees, 0..360 degrees
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_raw_ugv_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
+{
+    mavlink_message_t msg;
+    mavlink_msg_gps_raw_ugv_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, eph, epv, v, hdg);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_RAW UNPACKING
+
+/**
+ * @brief Get field usec from gps_raw message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_gps_raw_ugv_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field fix_type from gps_raw message
+ *
+ * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ */
+static inline uint8_t mavlink_msg_gps_raw_ugv_get_fix_type(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
+}
+
+/**
+ * @brief Get field lat from gps_raw message
+ *
+ * @return Latitude in degrees
+ */
+static inline double mavlink_msg_gps_raw_ugv_get_lat(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
+    r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
+    r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
+    r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7];
+    return (double)r.d;
+}
+
+/**
+ * @brief Get field lon from gps_raw message
+ *
+ * @return Longitude in degrees
+ */
+static inline double mavlink_msg_gps_raw_ugv_get_lon(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[0];
+    r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[1];
+    r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[2];
+    r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[3];
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[4];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[5];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[6];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[7];
+    return (double)r.d;
+}
+
+/**
+ * @brief Get field eph from gps_raw message
+ *
+ * @return GPS HDOP
+ */
+static inline float mavlink_msg_gps_raw_ugv_get_eph(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field epv from gps_raw message
+ *
+ * @return GPS VDOP
+ */
+static inline float mavlink_msg_gps_raw_ugv_get_epv(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field v from gps_raw message
+ *
+ * @return GPS ground speed
+ */
+static inline float mavlink_msg_gps_raw_ugv_get_v(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field hdg from gps_raw message
+ *
+ * @return Compass heading in degrees, 0..360 degrees
+ */
+static inline float mavlink_msg_gps_raw_ugv_get_hdg(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a gps_raw message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_raw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_raw_ugv_decode(const mavlink_message_t* msg, mavlink_gps_raw_ugv_t* gps_raw)
+{
+    gps_raw->usec = mavlink_msg_gps_raw_ugv_get_usec(msg);
+    gps_raw->fix_type = mavlink_msg_gps_raw_ugv_get_fix_type(msg);
+    gps_raw->lat = mavlink_msg_gps_raw_ugv_get_lat(msg);
+    gps_raw->lon = mavlink_msg_gps_raw_ugv_get_lon(msg);
+    gps_raw->eph = mavlink_msg_gps_raw_ugv_get_eph(msg);
+    gps_raw->epv = mavlink_msg_gps_raw_ugv_get_epv(msg);
+    gps_raw->v = mavlink_msg_gps_raw_ugv_get_v(msg);
+    gps_raw->hdg = mavlink_msg_gps_raw_ugv_get_hdg(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_set_global_origin.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,184 @@
+// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
+
+#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
+
+typedef struct __mavlink_gps_set_global_origin_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	int32_t latitude; ///< global position * 1E7
+	int32_t longitude; ///< global position * 1E7
+	int32_t altitude; ///< global position * 1000
+
+} mavlink_gps_set_global_origin_t;
+
+
+
+/**
+ * @brief Pack a gps_set_global_origin 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 target_system System ID
+ * @param target_component Component ID
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
+	i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
+	i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_set_global_origin message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
+	i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
+	i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_set_global_origin struct into a 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 gps_set_global_origin C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin)
+{
+	return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude);
+}
+
+/**
+ * @brief Send a gps_set_global_origin message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+	mavlink_message_t msg;
+	mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, latitude, longitude, altitude);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
+
+/**
+ * @brief Get field target_system from gps_set_global_origin message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from gps_set_global_origin message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field latitude from gps_set_global_origin message
+ *
+ * @return global position * 1E7
+ */
+static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field longitude from gps_set_global_origin message
+ *
+ * @return global position * 1E7
+ */
+static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field altitude from gps_set_global_origin message
+ *
+ * @return global position * 1000
+ */
+static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Decode a gps_set_global_origin message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_set_global_origin C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin)
+{
+	gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
+	gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
+	gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg);
+	gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg);
+	gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_gps_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,201 @@
+// MESSAGE GPS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_GPS_STATUS 27
+
+typedef struct __mavlink_gps_status_t 
+{
+	uint8_t satellites_visible; ///< Number of satellites visible
+	int8_t satellite_prn[20]; ///< Global satellite ID
+	int8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
+	int8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+	int8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
+	int8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
+
+} mavlink_gps_status_t;
+
+#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
+
+
+/**
+ * @brief Pack a gps_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 satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
+
+	i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
+	i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
+	i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
+	i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+	i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
+	i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_status message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
+
+	i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
+	i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
+	i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
+	i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+	i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
+	i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_status struct into a 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 gps_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
+{
+	return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
+}
+
+/**
+ * @brief Send a gps_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
+{
+	mavlink_message_t msg;
+	mavlink_msg_gps_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_STATUS UNPACKING
+
+/**
+ * @brief Get field satellites_visible from gps_status message
+ *
+ * @return Number of satellites visible
+ */
+static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field satellite_prn from gps_status message
+ *
+ * @return Global satellite ID
+ */
+static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t), 20);
+	return 20;
+}
+
+/**
+ * @brief Get field satellite_used from gps_status message
+ *
+ * @return 0: Satellite not used, 1: used for localization
+ */
+static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+20, 20);
+	return 20;
+}
+
+/**
+ * @brief Get field satellite_elevation from gps_status message
+ *
+ * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ */
+static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20, 20);
+	return 20;
+}
+
+/**
+ * @brief Get field satellite_azimuth from gps_status message
+ *
+ * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
+ */
+static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20, 20);
+	return 20;
+}
+
+/**
+ * @brief Get field satellite_snr from gps_status message
+ *
+ * @return Signal to noise ratio of satellite
+ */
+static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20+20, 20);
+	return 20;
+}
+
+/**
+ * @brief Decode a gps_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
+{
+	gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
+	mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
+	mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
+	mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
+	mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
+	mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_heartbeat.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,135 @@
+// MESSAGE HEARTBEAT PACKING
+
+#define MAVLINK_MSG_ID_HEARTBEAT 0
+
+typedef struct __mavlink_heartbeat_t 
+{
+    uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+    uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+    uint8_t mavlink_version; ///< MAVLink version
+
+} mavlink_heartbeat_t;
+
+
+
+/**
+ * @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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE 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 basic_mode, uint32_t custom_mode, uint8_t system_state)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+
+    i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+    i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+    i += put_uint8_t_by_index(basic_mode, i, msg->payload);
+    i += put_uint32_t_by_index(custom_mode, i, msg->payload);
+    i += put_uint8_t_by_index(system_state, i, msg->payload);
+    i += put_uint8_t_by_index(3, i, msg->payload); // MAVLink version
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was 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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE 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)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+
+    i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+    i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+    i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a heartbeat struct into a 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 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);
+}*/
+
+/**
+ * @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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
+{
+    mavlink_message_t msg;
+    mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot);
+    mavlink_send_uart(chan, &msg);
+}
+
+#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 (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field autopilot from heartbeat message
+ *
+ * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @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 (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @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)
+{
+    heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
+    heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
+    heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_hil_controls.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,232 @@
+// MESSAGE HIL_CONTROLS PACKING
+
+#define MAVLINK_MSG_ID_HIL_CONTROLS 68
+
+typedef struct __mavlink_hil_controls_t 
+{
+	uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	float roll_ailerons; ///< Control output -3 .. 1
+	float pitch_elevator; ///< Control output -1 .. 1
+	float yaw_rudder; ///< Control output -1 .. 1
+	float throttle; ///< Throttle 0 .. 1
+	uint8_t mode; ///< System mode (MAV_MODE)
+	uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
+
+} mavlink_hil_controls_t;
+
+
+
+/**
+ * @brief Pack a hil_controls 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_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll_ailerons Control output -3 .. 1
+ * @param pitch_elevator Control output -1 .. 1
+ * @param yaw_rudder Control output -1 .. 1
+ * @param throttle Throttle 0 .. 1
+ * @param mode System mode (MAV_MODE)
+ * @param nav_mode Navigation mode (MAV_NAV_MODE)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
+	i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
+	i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
+	i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
+	i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a hil_controls message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll_ailerons Control output -3 .. 1
+ * @param pitch_elevator Control output -1 .. 1
+ * @param yaw_rudder Control output -1 .. 1
+ * @param throttle Throttle 0 .. 1
+ * @param mode System mode (MAV_MODE)
+ * @param nav_mode Navigation mode (MAV_NAV_MODE)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
+	i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
+	i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
+	i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
+	i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a hil_controls struct into a 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 hil_controls C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
+{
+	return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->mode, hil_controls->nav_mode);
+}
+
+/**
+ * @brief Send a hil_controls message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll_ailerons Control output -3 .. 1
+ * @param pitch_elevator Control output -1 .. 1
+ * @param yaw_rudder Control output -1 .. 1
+ * @param throttle Throttle 0 .. 1
+ * @param mode System mode (MAV_MODE)
+ * @param nav_mode Navigation mode (MAV_NAV_MODE)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
+{
+	mavlink_message_t msg;
+	mavlink_msg_hil_controls_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE HIL_CONTROLS UNPACKING
+
+/**
+ * @brief Get field time_us from hil_controls message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll_ailerons from hil_controls message
+ *
+ * @return Control output -3 .. 1
+ */
+static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch_elevator from hil_controls message
+ *
+ * @return Control output -1 .. 1
+ */
+static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw_rudder from hil_controls message
+ *
+ * @return Control output -1 .. 1
+ */
+static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field throttle from hil_controls message
+ *
+ * @return Throttle 0 .. 1
+ */
+static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field mode from hil_controls message
+ *
+ * @return System mode (MAV_MODE)
+ */
+static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+}
+
+/**
+ * @brief Get field nav_mode from hil_controls message
+ *
+ * @return Navigation mode (MAV_NAV_MODE)
+ */
+static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a hil_controls message into a struct
+ *
+ * @param msg The message to decode
+ * @param hil_controls C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
+{
+	hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
+	hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
+	hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
+	hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
+	hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
+	hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
+	hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_hil_state.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,428 @@
+// MESSAGE HIL_STATE PACKING
+
+#define MAVLINK_MSG_ID_HIL_STATE 67
+
+typedef struct __mavlink_hil_state_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	float roll; ///< Roll angle (rad)
+	float pitch; ///< Pitch angle (rad)
+	float yaw; ///< Yaw angle (rad)
+	float rollspeed; ///< Roll angular speed (rad/s)
+	float pitchspeed; ///< Pitch angular speed (rad/s)
+	float yawspeed; ///< Yaw angular speed (rad/s)
+	int32_t lat; ///< Latitude, expressed as * 1E7
+	int32_t lon; ///< Longitude, expressed as * 1E7
+	int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
+	int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
+	int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
+	int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
+	int16_t xacc; ///< X acceleration (mg)
+	int16_t yacc; ///< Y acceleration (mg)
+	int16_t zacc; ///< Z acceleration (mg)
+
+} mavlink_hil_state_t;
+
+
+
+/**
+ * @brief Pack a hil_state 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+	i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+	i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+	i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+	i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+	i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+	i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+	i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a hil_state message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
+	i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
+	i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
+	i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
+	i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+	i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
+	i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
+	i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
+	i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a hil_state struct into a 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 hil_state C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
+{
+	return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
+}
+
+/**
+ * @brief Send a hil_state message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param roll Roll angle (rad)
+ * @param pitch Pitch angle (rad)
+ * @param yaw Yaw angle (rad)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s * 100
+ * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
+ * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
+ * @param xacc X acceleration (mg)
+ * @param yacc Y acceleration (mg)
+ * @param zacc Z acceleration (mg)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+	mavlink_message_t msg;
+	mavlink_msg_hil_state_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE HIL_STATE UNPACKING
+
+/**
+ * @brief Get field usec from hil_state message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_hil_state_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll from hil_state message
+ *
+ * @return Roll angle (rad)
+ */
+static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from hil_state message
+ *
+ * @return Pitch angle (rad)
+ */
+static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from hil_state message
+ *
+ * @return Yaw angle (rad)
+ */
+static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field rollspeed from hil_state message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitchspeed from hil_state message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yawspeed from hil_state message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lat from hil_state message
+ *
+ * @return Latitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field lon from hil_state message
+ *
+ * @return Longitude, expressed as * 1E7
+ */
+static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field alt from hil_state message
+ *
+ * @return Altitude in meters, expressed as * 1000 (millimeters)
+ */
+static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field vx from hil_state message
+ *
+ * @return Ground X Speed (Latitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vy from hil_state message
+ *
+ * @return Ground Y Speed (Longitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field vz from hil_state message
+ *
+ * @return Ground Z Speed (Altitude), expressed as m/s * 100
+ */
+static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field xacc from hil_state message
+ *
+ * @return X acceleration (mg)
+ */
+static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field yacc from hil_state message
+ *
+ * @return Y acceleration (mg)
+ */
+static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field zacc from hil_state message
+ *
+ * @return Z acceleration (mg)
+ */
+static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a hil_state message into a struct
+ *
+ * @param msg The message to decode
+ * @param hil_state C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
+{
+	hil_state->usec = mavlink_msg_hil_state_get_usec(msg);
+	hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
+	hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
+	hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
+	hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
+	hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
+	hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
+	hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
+	hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
+	hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
+	hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
+	hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
+	hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
+	hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
+	hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
+	hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_local_position.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE LOCAL_POSITION PACKING
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION 31
+
+typedef struct __mavlink_local_position_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds 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_t;
+
+
+
+/**
+ * @brief Pack a local_position 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 usec Timestamp (microseconds since UNIX epoch or microseconds 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_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_float_by_index(x, i, msg->payload); // X Position
+    i += put_float_by_index(y, i, msg->payload); // Y Position
+    i += put_float_by_index(z, i, msg->payload); // Z Position
+    i += put_float_by_index(vx, i, msg->payload); // X Speed
+    i += put_float_by_index(vy, i, msg->payload); // Y Speed
+    i += put_float_by_index(vz, i, msg->payload); // Z Speed
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a local_position message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds 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_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_float_by_index(x, i, msg->payload); // X Position
+    i += put_float_by_index(y, i, msg->payload); // Y Position
+    i += put_float_by_index(z, i, msg->payload); // Z Position
+    i += put_float_by_index(vx, i, msg->payload); // X Speed
+    i += put_float_by_index(vy, i, msg->payload); // Y Speed
+    i += put_float_by_index(vz, i, msg->payload); // Z Speed
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a local_position struct into a 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 local_position C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position)
+{
+    return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz);
+}
+
+/**
+ * @brief Send a local_position message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds 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_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
+{
+    mavlink_message_t msg;
+    mavlink_msg_local_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, vx, vy, vz);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE LOCAL_POSITION UNPACKING
+
+/**
+ * @brief Get field usec from local_position message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_local_position_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from local_position message
+ *
+ * @return X Position
+ */
+static inline float mavlink_msg_local_position_get_x(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field y from local_position message
+ *
+ * @return Y Position
+ */
+static inline float mavlink_msg_local_position_get_y(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field z from local_position message
+ *
+ * @return Z Position
+ */
+static inline float mavlink_msg_local_position_get_z(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vx from local_position message
+ *
+ * @return X Speed
+ */
+static inline float mavlink_msg_local_position_get_vx(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vy from local_position message
+ *
+ * @return Y Speed
+ */
+static inline float mavlink_msg_local_position_get_vy(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field vz from local_position message
+ *
+ * @return Z Speed
+ */
+static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a local_position message into a struct
+ *
+ * @param msg The message to decode
+ * @param local_position C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position)
+{
+    local_position->usec = mavlink_msg_local_position_get_usec(msg);
+    local_position->x = mavlink_msg_local_position_get_x(msg);
+    local_position->y = mavlink_msg_local_position_get_y(msg);
+    local_position->z = mavlink_msg_local_position_get_z(msg);
+    local_position->vx = mavlink_msg_local_position_get_vx(msg);
+    local_position->vy = mavlink_msg_local_position_get_vy(msg);
+    local_position->vz = mavlink_msg_local_position_get_vz(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_local_position_setpoint.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,172 @@
+// MESSAGE LOCAL_POSITION_SETPOINT PACKING
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51
+
+typedef struct __mavlink_local_position_setpoint_t 
+{
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float yaw; ///< Desired yaw angle
+
+} mavlink_local_position_setpoint_t;
+
+
+
+/**
+ * @brief Pack a local_position_setpoint 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 x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
+
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a local_position_setpoint message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
+
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a local_position_setpoint struct into a 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 local_position_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
+{
+	return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
+}
+
+/**
+ * @brief Send a local_position_setpoint message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_local_position_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
+
+/**
+ * @brief Get field x from local_position_setpoint message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from local_position_setpoint message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from local_position_setpoint message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from local_position_setpoint message
+ *
+ * @return Desired yaw angle
+ */
+static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a local_position_setpoint message into a struct
+ *
+ * @param msg The message to decode
+ * @param local_position_setpoint C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint)
+{
+	local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg);
+	local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg);
+	local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
+	local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_local_position_setpoint_set.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,206 @@
+// MESSAGE LOCAL_POSITION_SETPOINT_SET PACKING
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET 50
+
+typedef struct __mavlink_local_position_setpoint_set_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float yaw; ///< Desired yaw angle
+
+} mavlink_local_position_setpoint_set_t;
+
+
+
+/**
+ * @brief Pack a local_position_setpoint_set 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 target_system System ID
+ * @param target_component Component ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a local_position_setpoint_set message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a local_position_setpoint_set struct into a 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 local_position_setpoint_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
+{
+	return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw);
+}
+
+/**
+ * @brief Send a local_position_setpoint_set message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw Desired yaw angle
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_local_position_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE LOCAL_POSITION_SETPOINT_SET UNPACKING
+
+/**
+ * @brief Get field target_system from local_position_setpoint_set message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from local_position_setpoint_set message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field x from local_position_setpoint_set message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from local_position_setpoint_set message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from local_position_setpoint_set message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from local_position_setpoint_set message
+ *
+ * @return Desired yaw angle
+ */
+static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a local_position_setpoint_set message into a struct
+ *
+ * @param msg The message to decode
+ * @param local_position_setpoint_set C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
+{
+	local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg);
+	local_position_setpoint_set->target_component = mavlink_msg_local_position_setpoint_set_get_target_component(msg);
+	local_position_setpoint_set->x = mavlink_msg_local_position_setpoint_set_get_x(msg);
+	local_position_setpoint_set->y = mavlink_msg_local_position_setpoint_set_get_y(msg);
+	local_position_setpoint_set->z = mavlink_msg_local_position_setpoint_set_get_z(msg);
+	local_position_setpoint_set->yaw = mavlink_msg_local_position_setpoint_set_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_manual_control.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,257 @@
+// MESSAGE MANUAL_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_MANUAL_CONTROL 69
+
+typedef struct __mavlink_manual_control_t 
+{
+	uint8_t target; ///< The system to be controlled
+	float roll; ///< roll
+	float pitch; ///< pitch
+	float yaw; ///< yaw
+	float thrust; ///< thrust
+	uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
+	uint8_t pitch_manual; ///< pitch auto:0, manual:1
+	uint8_t yaw_manual; ///< yaw auto:0, manual:1
+	uint8_t thrust_manual; ///< thrust auto:0, manual:1
+
+} mavlink_manual_control_t;
+
+
+
+/**
+ * @brief Pack a manual_control 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 target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
+	i += put_float_by_index(roll, i, msg->payload); // roll
+	i += put_float_by_index(pitch, i, msg->payload); // pitch
+	i += put_float_by_index(yaw, i, msg->payload); // yaw
+	i += put_float_by_index(thrust, i, msg->payload); // thrust
+	i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
+	i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
+	i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
+	i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a manual_control message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
+	i += put_float_by_index(roll, i, msg->payload); // roll
+	i += put_float_by_index(pitch, i, msg->payload); // pitch
+	i += put_float_by_index(yaw, i, msg->payload); // yaw
+	i += put_float_by_index(thrust, i, msg->payload); // thrust
+	i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
+	i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
+	i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
+	i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a manual_control struct into a 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 manual_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
+{
+	return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
+}
+
+/**
+ * @brief Send a manual_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	mavlink_message_t msg;
+	mavlink_msg_manual_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE MANUAL_CONTROL UNPACKING
+
+/**
+ * @brief Get field target from manual_control message
+ *
+ * @return The system to be controlled
+ */
+static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field roll from manual_control message
+ *
+ * @return roll
+ */
+static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from manual_control message
+ *
+ * @return pitch
+ */
+static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from manual_control message
+ *
+ * @return yaw
+ */
+static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from manual_control message
+ *
+ * @return thrust
+ */
+static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll_manual from manual_control message
+ *
+ * @return roll control enabled auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+}
+
+/**
+ * @brief Get field pitch_manual from manual_control message
+ *
+ * @return pitch auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field yaw_manual from manual_control message
+ *
+ * @return yaw auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field thrust_manual from manual_control message
+ *
+ * @return thrust auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a manual_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param manual_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
+{
+	manual_control->target = mavlink_msg_manual_control_get_target(msg);
+	manual_control->roll = mavlink_msg_manual_control_get_roll(msg);
+	manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg);
+	manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg);
+	manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg);
+	manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg);
+	manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg);
+	manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg);
+	manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_named_value_float.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,126 @@
+// MESSAGE NAMED_VALUE_FLOAT PACKING
+
+#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252
+
+typedef struct __mavlink_named_value_float_t 
+{
+	char name[10]; ///< Name of the debug variable
+	float value; ///< Floating point value
+
+} mavlink_named_value_float_t;
+
+#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
+
+
+/**
+ * @brief Pack a named_value_float 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 name Name of the debug variable
+ * @param value Floating point value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, float value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
+	i += put_float_by_index(value, i, msg->payload); // Floating point value
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a named_value_float message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param name Name of the debug variable
+ * @param value Floating point value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, float value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
+	i += put_float_by_index(value, i, msg->payload); // Floating point value
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a named_value_float struct into a 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 named_value_float C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
+{
+	return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value);
+}
+
+/**
+ * @brief Send a named_value_float message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param name Name of the debug variable
+ * @param value Floating point value
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char* name, float value)
+{
+	mavlink_message_t msg;
+	mavlink_msg_named_value_float_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE NAMED_VALUE_FLOAT UNPACKING
+
+/**
+ * @brief Get field name from named_value_float message
+ *
+ * @return Name of the debug variable
+ */
+static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload, sizeof(char)*10);
+	return sizeof(char)*10;
+}
+
+/**
+ * @brief Get field value from named_value_float message
+ *
+ * @return Floating point value
+ */
+static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(char)*10)[0];
+	r.b[2] = (msg->payload+sizeof(char)*10)[1];
+	r.b[1] = (msg->payload+sizeof(char)*10)[2];
+	r.b[0] = (msg->payload+sizeof(char)*10)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a named_value_float message into a struct
+ *
+ * @param msg The message to decode
+ * @param named_value_float C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
+{
+	mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
+	named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_named_value_int.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,126 @@
+// MESSAGE NAMED_VALUE_INT PACKING
+
+#define MAVLINK_MSG_ID_NAMED_VALUE_INT 253
+
+typedef struct __mavlink_named_value_int_t 
+{
+	char name[10]; ///< Name of the debug variable
+	int32_t value; ///< Signed integer value
+
+} mavlink_named_value_int_t;
+
+#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
+
+
+/**
+ * @brief Pack a named_value_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 name Name of the debug variable
+ * @param value Signed integer value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, int32_t value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
+	i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a named_value_int message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param name Name of the debug variable
+ * @param value Signed integer value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, int32_t value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
+
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
+	i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a named_value_int struct into a 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 named_value_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
+{
+	return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->name, named_value_int->value);
+}
+
+/**
+ * @brief Send a named_value_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param name Name of the debug variable
+ * @param value Signed integer value
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, const char* name, int32_t value)
+{
+	mavlink_message_t msg;
+	mavlink_msg_named_value_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE NAMED_VALUE_INT UNPACKING
+
+/**
+ * @brief Get field name from named_value_int message
+ *
+ * @return Name of the debug variable
+ */
+static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload, sizeof(char)*10);
+	return sizeof(char)*10;
+}
+
+/**
+ * @brief Get field value from named_value_int message
+ *
+ * @return Signed integer value
+ */
+static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(char)*10)[0];
+	r.b[2] = (msg->payload+sizeof(char)*10)[1];
+	r.b[1] = (msg->payload+sizeof(char)*10)[2];
+	r.b[0] = (msg->payload+sizeof(char)*10)[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Decode a named_value_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param named_value_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
+{
+	mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
+	named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_nav_controller_output.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,254 @@
+// MESSAGE NAV_CONTROLLER_OUTPUT PACKING
+
+#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
+
+typedef struct __mavlink_nav_controller_output_t 
+{
+	float nav_roll; ///< Current desired roll in degrees
+	float nav_pitch; ///< Current desired pitch in degrees
+	int16_t nav_bearing; ///< Current desired heading in degrees
+	int16_t target_bearing; ///< Bearing to current waypoint/target in degrees
+	uint16_t wp_dist; ///< Distance to active waypoint in meters
+	float alt_error; ///< Current altitude error in meters
+	float aspd_error; ///< Current airspeed error in meters/second
+	float xtrack_error; ///< Current crosstrack error on x-y plane in meters
+
+} mavlink_nav_controller_output_t;
+
+
+
+/**
+ * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees
+ * @param nav_pitch Current desired pitch in degrees
+ * @param nav_bearing Current desired heading in degrees
+ * @param target_bearing Bearing to current waypoint/target in degrees
+ * @param wp_dist Distance to active waypoint in meters
+ * @param alt_error Current altitude error in meters
+ * @param aspd_error Current airspeed error in meters/second
+ * @param xtrack_error Current crosstrack error on x-y plane in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
+
+	i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees
+	i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees
+	i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees
+	i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees
+	i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters
+	i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters
+	i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second
+	i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a nav_controller_output message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param nav_roll Current desired roll in degrees
+ * @param nav_pitch Current desired pitch in degrees
+ * @param nav_bearing Current desired heading in degrees
+ * @param target_bearing Bearing to current waypoint/target in degrees
+ * @param wp_dist Distance to active waypoint in meters
+ * @param alt_error Current altitude error in meters
+ * @param aspd_error Current airspeed error in meters/second
+ * @param xtrack_error Current crosstrack error on x-y plane in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
+
+	i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees
+	i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees
+	i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees
+	i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees
+	i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters
+	i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters
+	i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second
+	i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a nav_controller_output struct into a 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 nav_controller_output C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
+{
+	return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
+}
+
+/**
+ * @brief Send a nav_controller_output message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param nav_roll Current desired roll in degrees
+ * @param nav_pitch Current desired pitch in degrees
+ * @param nav_bearing Current desired heading in degrees
+ * @param target_bearing Bearing to current waypoint/target in degrees
+ * @param wp_dist Distance to active waypoint in meters
+ * @param alt_error Current altitude error in meters
+ * @param aspd_error Current airspeed error in meters/second
+ * @param xtrack_error Current crosstrack error on x-y plane in meters
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
+{
+	mavlink_message_t msg;
+	mavlink_msg_nav_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING
+
+/**
+ * @brief Get field nav_roll from nav_controller_output message
+ *
+ * @return Current desired roll in degrees
+ */
+static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field nav_pitch from nav_controller_output message
+ *
+ * @return Current desired pitch in degrees
+ */
+static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field nav_bearing from nav_controller_output message
+ *
+ * @return Current desired heading in degrees
+ */
+static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field target_bearing from nav_controller_output message
+ *
+ * @return Bearing to current waypoint/target in degrees
+ */
+static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field wp_dist from nav_controller_output message
+ *
+ * @return Distance to active waypoint in meters
+ */
+static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field alt_error from nav_controller_output message
+ *
+ * @return Current altitude error in meters
+ */
+static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field aspd_error from nav_controller_output message
+ *
+ * @return Current airspeed error in meters/second
+ */
+static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field xtrack_error from nav_controller_output message
+ *
+ * @return Current crosstrack error on x-y plane in meters
+ */
+static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a nav_controller_output message into a struct
+ *
+ * @param msg The message to decode
+ * @param nav_controller_output C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output)
+{
+	nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg);
+	nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg);
+	nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg);
+	nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg);
+	nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
+	nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
+	nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
+	nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_object_detection_event.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,224 @@
+// MESSAGE OBJECT_DETECTION_EVENT PACKING
+
+#define MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT 140
+
+typedef struct __mavlink_object_detection_event_t 
+{
+	uint32_t time; ///< Timestamp in milliseconds since system boot
+	uint16_t object_id; ///< Object ID
+	uint8_t type; ///< Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+	char name[20]; ///< Name of the object as defined by the detector
+	uint8_t quality; ///< Detection quality / confidence. 0: bad, 255: maximum confidence
+	float bearing; ///< Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+	float distance; ///< Ground distance in meters
+
+} mavlink_object_detection_event_t;
+
+#define MAVLINK_MSG_OBJECT_DETECTION_EVENT_FIELD_NAME_LEN 20
+
+
+/**
+ * @brief Pack a object_detection_event 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 Timestamp in milliseconds since system boot
+ * @param object_id Object ID
+ * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+ * @param name Name of the object as defined by the detector
+ * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
+ * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+ * @param distance Ground distance in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_object_detection_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t time, uint16_t object_id, uint8_t type, const char* name, uint8_t quality, float bearing, float distance)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT;
+
+	i += put_uint32_t_by_index(time, i, msg->payload); // Timestamp in milliseconds since system boot
+	i += put_uint16_t_by_index(object_id, i, msg->payload); // Object ID
+	i += put_uint8_t_by_index(type, i, msg->payload); // Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*20, i, msg->payload); // Name of the object as defined by the detector
+	i += put_uint8_t_by_index(quality, i, msg->payload); // Detection quality / confidence. 0: bad, 255: maximum confidence
+	i += put_float_by_index(bearing, i, msg->payload); // Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+	i += put_float_by_index(distance, i, msg->payload); // Ground distance in meters
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a object_detection_event message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time Timestamp in milliseconds since system boot
+ * @param object_id Object ID
+ * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+ * @param name Name of the object as defined by the detector
+ * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
+ * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+ * @param distance Ground distance in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_object_detection_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t time, uint16_t object_id, uint8_t type, const char* name, uint8_t quality, float bearing, float distance)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT;
+
+	i += put_uint32_t_by_index(time, i, msg->payload); // Timestamp in milliseconds since system boot
+	i += put_uint16_t_by_index(object_id, i, msg->payload); // Object ID
+	i += put_uint8_t_by_index(type, i, msg->payload); // Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+	i += put_array_by_index((const int8_t*)name, sizeof(char)*20, i, msg->payload); // Name of the object as defined by the detector
+	i += put_uint8_t_by_index(quality, i, msg->payload); // Detection quality / confidence. 0: bad, 255: maximum confidence
+	i += put_float_by_index(bearing, i, msg->payload); // Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+	i += put_float_by_index(distance, i, msg->payload); // Ground distance in meters
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a object_detection_event struct into a 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 object_detection_event C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_object_detection_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_object_detection_event_t* object_detection_event)
+{
+	return mavlink_msg_object_detection_event_pack(system_id, component_id, msg, object_detection_event->time, object_detection_event->object_id, object_detection_event->type, object_detection_event->name, object_detection_event->quality, object_detection_event->bearing, object_detection_event->distance);
+}
+
+/**
+ * @brief Send a object_detection_event message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time Timestamp in milliseconds since system boot
+ * @param object_id Object ID
+ * @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+ * @param name Name of the object as defined by the detector
+ * @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
+ * @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+ * @param distance Ground distance in meters
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_object_detection_event_send(mavlink_channel_t chan, uint32_t time, uint16_t object_id, uint8_t type, const char* name, uint8_t quality, float bearing, float distance)
+{
+	mavlink_message_t msg;
+	mavlink_msg_object_detection_event_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time, object_id, type, name, quality, bearing, distance);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE OBJECT_DETECTION_EVENT UNPACKING
+
+/**
+ * @brief Get field time from object_detection_event message
+ *
+ * @return Timestamp in milliseconds since system boot
+ */
+static inline uint32_t mavlink_msg_object_detection_event_get_time(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field object_id from object_detection_event message
+ *
+ * @return Object ID
+ */
+static inline uint16_t mavlink_msg_object_detection_event_get_object_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint32_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint32_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field type from object_detection_event message
+ *
+ * @return Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+ */
+static inline uint8_t mavlink_msg_object_detection_event_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Get field name from object_detection_event message
+ *
+ * @return Name of the object as defined by the detector
+ */
+static inline uint16_t mavlink_msg_object_detection_event_get_name(const mavlink_message_t* msg, char* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t), sizeof(char)*20);
+	return sizeof(char)*20;
+}
+
+/**
+ * @brief Get field quality from object_detection_event message
+ *
+ * @return Detection quality / confidence. 0: bad, 255: maximum confidence
+ */
+static inline uint8_t mavlink_msg_object_detection_event_get_quality(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20)[0];
+}
+
+/**
+ * @brief Get field bearing from object_detection_event message
+ *
+ * @return Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+ */
+static inline float mavlink_msg_object_detection_event_get_bearing(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field distance from object_detection_event message
+ *
+ * @return Ground distance in meters
+ */
+static inline float mavlink_msg_object_detection_event_get_distance(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(char)*20+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a object_detection_event message into a struct
+ *
+ * @param msg The message to decode
+ * @param object_detection_event C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_object_detection_event_decode(const mavlink_message_t* msg, mavlink_object_detection_event_t* object_detection_event)
+{
+	object_detection_event->time = mavlink_msg_object_detection_event_get_time(msg);
+	object_detection_event->object_id = mavlink_msg_object_detection_event_get_object_id(msg);
+	object_detection_event->type = mavlink_msg_object_detection_event_get_type(msg);
+	mavlink_msg_object_detection_event_get_name(msg, object_detection_event->name);
+	object_detection_event->quality = mavlink_msg_object_detection_event_get_quality(msg);
+	object_detection_event->bearing = mavlink_msg_object_detection_event_get_bearing(msg);
+	object_detection_event->distance = mavlink_msg_object_detection_event_get_distance(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_optical_flow.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,206 @@
+// MESSAGE OPTICAL_FLOW PACKING
+
+#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
+
+typedef struct __mavlink_optical_flow_t 
+{
+	uint64_t time; ///< Timestamp (UNIX)
+	uint8_t sensor_id; ///< Sensor ID
+	int16_t flow_x; ///< Flow in pixels in x-sensor direction
+	int16_t flow_y; ///< Flow in pixels in y-sensor direction
+	uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
+	float ground_distance; ///< Ground distance in meters
+
+} mavlink_optical_flow_t;
+
+
+
+/**
+ * @brief Pack a optical_flow 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 Timestamp (UNIX)
+ * @param sensor_id Sensor ID
+ * @param flow_x Flow in pixels in x-sensor direction
+ * @param flow_y Flow in pixels in y-sensor direction
+ * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
+ * @param ground_distance Ground distance in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
+
+	i += put_uint64_t_by_index(time, i, msg->payload); // Timestamp (UNIX)
+	i += put_uint8_t_by_index(sensor_id, i, msg->payload); // Sensor ID
+	i += put_int16_t_by_index(flow_x, i, msg->payload); // Flow in pixels in x-sensor direction
+	i += put_int16_t_by_index(flow_y, i, msg->payload); // Flow in pixels in y-sensor direction
+	i += put_uint8_t_by_index(quality, i, msg->payload); // Optical flow quality / confidence. 0: bad, 255: maximum quality
+	i += put_float_by_index(ground_distance, i, msg->payload); // Ground distance in meters
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a optical_flow message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time Timestamp (UNIX)
+ * @param sensor_id Sensor ID
+ * @param flow_x Flow in pixels in x-sensor direction
+ * @param flow_y Flow in pixels in y-sensor direction
+ * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
+ * @param ground_distance Ground distance in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
+
+	i += put_uint64_t_by_index(time, i, msg->payload); // Timestamp (UNIX)
+	i += put_uint8_t_by_index(sensor_id, i, msg->payload); // Sensor ID
+	i += put_int16_t_by_index(flow_x, i, msg->payload); // Flow in pixels in x-sensor direction
+	i += put_int16_t_by_index(flow_y, i, msg->payload); // Flow in pixels in y-sensor direction
+	i += put_uint8_t_by_index(quality, i, msg->payload); // Optical flow quality / confidence. 0: bad, 255: maximum quality
+	i += put_float_by_index(ground_distance, i, msg->payload); // Ground distance in meters
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a optical_flow struct into a 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 optical_flow C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
+{
+	return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
+}
+
+/**
+ * @brief Send a optical_flow message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time Timestamp (UNIX)
+ * @param sensor_id Sensor ID
+ * @param flow_x Flow in pixels in x-sensor direction
+ * @param flow_y Flow in pixels in y-sensor direction
+ * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
+ * @param ground_distance Ground distance in meters
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
+{
+	mavlink_message_t msg;
+	mavlink_msg_optical_flow_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time, sensor_id, flow_x, flow_y, quality, ground_distance);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE OPTICAL_FLOW UNPACKING
+
+/**
+ * @brief Get field time from optical_flow message
+ *
+ * @return Timestamp (UNIX)
+ */
+static inline uint64_t mavlink_msg_optical_flow_get_time(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field sensor_id from optical_flow message
+ *
+ * @return Sensor ID
+ */
+static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
+}
+
+/**
+ * @brief Get field flow_x from optical_flow message
+ *
+ * @return Flow in pixels in x-sensor direction
+ */
+static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field flow_y from optical_flow message
+ *
+ * @return Flow in pixels in y-sensor direction
+ */
+static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field quality from optical_flow message
+ *
+ * @return Optical flow quality / confidence. 0: bad, 255: maximum quality
+ */
+static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+}
+
+/**
+ * @brief Get field ground_distance from optical_flow message
+ *
+ * @return Ground distance in meters
+ */
+static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a optical_flow message into a struct
+ *
+ * @param msg The message to decode
+ * @param optical_flow C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
+{
+	optical_flow->time = mavlink_msg_optical_flow_get_time(msg);
+	optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
+	optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
+	optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
+	optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
+	optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_param_request_list.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE PARAM_REQUEST_LIST PACKING
+
+#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21
+
+typedef struct __mavlink_param_request_list_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+
+} mavlink_param_request_list_t;
+
+
+
+/**
+ * @brief Pack a param_request_list 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 target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a param_request_list message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a param_request_list struct into a 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 param_request_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
+{
+	return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
+}
+
+/**
+ * @brief Send a param_request_list message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+	mavlink_message_t msg;
+	mavlink_msg_param_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PARAM_REQUEST_LIST UNPACKING
+
+/**
+ * @brief Get field target_system from param_request_list message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from param_request_list message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a param_request_list message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_request_list C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list)
+{
+	param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg);
+	param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_param_request_read.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,158 @@
+// MESSAGE PARAM_REQUEST_READ PACKING
+
+#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
+
+typedef struct __mavlink_param_request_read_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	int8_t param_id[15]; ///< Onboard parameter id
+	int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
+
+} mavlink_param_request_read_t;
+
+#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 15
+
+
+/**
+ * @brief Pack a param_request_read 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 target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_index Parameter index. Send -1 to use the param ID field as identifier
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a param_request_read message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_index Parameter index. Send -1 to use the param ID field as identifier
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a param_request_read struct into a 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 param_request_read C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
+{
+	return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
+}
+
+/**
+ * @brief Send a param_request_read message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_index Parameter index. Send -1 to use the param ID field as identifier
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index)
+{
+	mavlink_message_t msg;
+	mavlink_msg_param_request_read_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_index);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PARAM_REQUEST_READ UNPACKING
+
+/**
+ * @brief Get field target_system from param_request_read message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from param_request_read message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field param_id from param_request_read message
+ *
+ * @return Onboard parameter id
+ */
+static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15);
+	return 15;
+}
+
+/**
+ * @brief Get field param_index from param_request_read message
+ *
+ * @return Parameter index. Send -1 to use the param ID field as identifier
+ */
+static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a param_request_read message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_request_read C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
+{
+	param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);
+	param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg);
+	mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id);
+	param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_param_set.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,160 @@
+// MESSAGE PARAM_SET PACKING
+
+#define MAVLINK_MSG_ID_PARAM_SET 23
+
+typedef struct __mavlink_param_set_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	int8_t param_id[15]; ///< Onboard parameter id
+	float param_value; ///< Onboard parameter value
+
+} mavlink_param_set_t;
+
+#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15
+
+
+/**
+ * @brief Pack a param_set 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 target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a param_set message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a param_set struct into a 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 param_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
+{
+	return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value);
+}
+
+/**
+ * @brief Send a param_set message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
+{
+	mavlink_message_t msg;
+	mavlink_msg_param_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_value);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PARAM_SET UNPACKING
+
+/**
+ * @brief Get field target_system from param_set message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from param_set message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field param_id from param_set message
+ *
+ * @return Onboard parameter id
+ */
+static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15);
+	return 15;
+}
+
+/**
+ * @brief Get field param_value from param_set message
+ *
+ * @return Onboard parameter value
+ */
+static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a param_set message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_set C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
+{
+	param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
+	param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
+	mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
+	param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_param_value.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,166 @@
+// MESSAGE PARAM_VALUE PACKING
+
+#define MAVLINK_MSG_ID_PARAM_VALUE 22
+
+typedef struct __mavlink_param_value_t 
+{
+	int8_t param_id[15]; ///< Onboard parameter id
+	float param_value; ///< Onboard parameter value
+	uint16_t param_count; ///< Total number of onboard parameters
+	uint16_t param_index; ///< Index of this onboard parameter
+
+} mavlink_param_value_t;
+
+#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15
+
+
+/**
+ * @brief Pack a param_value 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 param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ * @param param_count Total number of onboard parameters
+ * @param param_index Index of this onboard parameter
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
+
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
+	i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
+	i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a param_value message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ * @param param_count Total number of onboard parameters
+ * @param param_index Index of this onboard parameter
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
+
+	i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
+	i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
+	i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
+	i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a param_value struct into a 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 param_value C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
+{
+	return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index);
+}
+
+/**
+ * @brief Send a param_value message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param param_id Onboard parameter id
+ * @param param_value Onboard parameter value
+ * @param param_count Total number of onboard parameters
+ * @param param_index Index of this onboard parameter
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
+{
+	mavlink_message_t msg;
+	mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, param_id, param_value, param_count, param_index);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PARAM_VALUE UNPACKING
+
+/**
+ * @brief Get field param_id from param_value message
+ *
+ * @return Onboard parameter id
+ */
+static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload, 15);
+	return 15;
+}
+
+/**
+ * @brief Get field param_value from param_value message
+ *
+ * @return Onboard parameter value
+ */
+static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+15)[0];
+	r.b[2] = (msg->payload+15)[1];
+	r.b[1] = (msg->payload+15)[2];
+	r.b[0] = (msg->payload+15)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param_count from param_value message
+ *
+ * @return Total number of onboard parameters
+ */
+static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+15+sizeof(float))[0];
+	r.b[0] = (msg->payload+15+sizeof(float))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field param_index from param_value message
+ *
+ * @return Index of this onboard parameter
+ */
+static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a param_value message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_value C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
+{
+	mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
+	param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
+	param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
+	param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_ping.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,166 @@
+// MESSAGE PING PACKING
+
+#define MAVLINK_MSG_ID_PING 3
+
+typedef struct __mavlink_ping_t 
+{
+	uint32_t seq; ///< PING sequence
+	uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+	uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+	uint64_t time; ///< Unix timestamp in microseconds
+
+} mavlink_ping_t;
+
+
+
+/**
+ * @brief Pack a ping 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 seq PING sequence
+ * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param time Unix timestamp in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PING;
+
+	i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+	i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a ping message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param seq PING sequence
+ * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param time Unix timestamp in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PING;
+
+	i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+	i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a ping struct into a 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 ping C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
+{
+	return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
+}
+
+/**
+ * @brief Send a ping message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param seq PING sequence
+ * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+ * @param time Unix timestamp in microseconds
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
+{
+	mavlink_message_t msg;
+	mavlink_msg_ping_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq, target_system, target_component, time);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PING UNPACKING
+
+/**
+ * @brief Get field seq from ping message
+ *
+ * @return PING sequence
+ */
+static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field target_system from ping message
+ *
+ * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
+ */
+static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint32_t))[0];
+}
+
+/**
+ * @brief Get field target_component from ping message
+ *
+ * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
+ */
+static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field time from ping message
+ *
+ * @return Unix timestamp in microseconds
+ */
+static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[6] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[5] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[4] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[4];
+	r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[5];
+	r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[6];
+	r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Decode a ping message into a struct
+ *
+ * @param msg The message to decode
+ * @param ping C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
+{
+	ping->seq = mavlink_msg_ping_get_seq(msg);
+	ping->target_system = mavlink_msg_ping_get_target_system(msg);
+	ping->target_component = mavlink_msg_ping_get_target_component(msg);
+	ping->time = mavlink_msg_ping_get_time(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_position_target.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,172 @@
+// MESSAGE POSITION_TARGET PACKING
+
+#define MAVLINK_MSG_ID_POSITION_TARGET 63
+
+typedef struct __mavlink_position_target_t 
+{
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float yaw; ///< yaw orientation in radians, 0 = NORTH
+
+} mavlink_position_target_t;
+
+
+
+/**
+ * @brief Pack a position_target 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 x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
+
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a position_target message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
+
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a position_target struct into a 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 position_target C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
+{
+	return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
+}
+
+/**
+ * @brief Send a position_target message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_position_target_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POSITION_TARGET UNPACKING
+
+/**
+ * @brief Get field x from position_target message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from position_target message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from position_target message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from position_target message
+ *
+ * @return yaw orientation in radians, 0 = NORTH
+ */
+static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a position_target message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_target C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
+{
+	position_target->x = mavlink_msg_position_target_get_x(msg);
+	position_target->y = mavlink_msg_position_target_get_y(msg);
+	position_target->z = mavlink_msg_position_target_get_z(msg);
+	position_target->yaw = mavlink_msg_position_target_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_raw_imu.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,290 @@
+// MESSAGE RAW_IMU PACKING
+
+#define MAVLINK_MSG_ID_RAW_IMU 28
+
+typedef struct __mavlink_raw_imu_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	int16_t xacc; ///< X acceleration (raw)
+	int16_t yacc; ///< Y acceleration (raw)
+	int16_t zacc; ///< Z acceleration (raw)
+	int16_t xgyro; ///< Angular speed around X axis (raw)
+	int16_t ygyro; ///< Angular speed around Y axis (raw)
+	int16_t zgyro; ///< Angular speed around Z axis (raw)
+	int16_t xmag; ///< X Magnetic field (raw)
+	int16_t ymag; ///< Y Magnetic field (raw)
+	int16_t zmag; ///< Z Magnetic field (raw)
+
+} mavlink_raw_imu_t;
+
+
+
+/**
+ * @brief Pack a raw_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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param xacc X acceleration (raw)
+ * @param yacc Y acceleration (raw)
+ * @param zacc Z acceleration (raw)
+ * @param xgyro Angular speed around X axis (raw)
+ * @param ygyro Angular speed around Y axis (raw)
+ * @param zgyro Angular speed around Z axis (raw)
+ * @param xmag X Magnetic field (raw)
+ * @param ymag Y Magnetic field (raw)
+ * @param zmag Z Magnetic field (raw)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, 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)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw)
+	i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw)
+	i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw)
+	i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw)
+	i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw)
+	i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw)
+	i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a raw_imu message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param xacc X acceleration (raw)
+ * @param yacc Y acceleration (raw)
+ * @param zacc Z acceleration (raw)
+ * @param xgyro Angular speed around X axis (raw)
+ * @param ygyro Angular speed around Y axis (raw)
+ * @param zgyro Angular speed around Z axis (raw)
+ * @param xmag X Magnetic field (raw)
+ * @param ymag Y Magnetic field (raw)
+ * @param zmag Z Magnetic field (raw)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, 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)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw)
+	i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw)
+	i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw)
+	i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw)
+	i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw)
+	i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw)
+	i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw)
+	i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw)
+	i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a raw_imu struct into a 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 raw_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
+{
+	return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
+}
+
+/**
+ * @brief Send a raw_imu message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param xacc X acceleration (raw)
+ * @param yacc Y acceleration (raw)
+ * @param zacc Z acceleration (raw)
+ * @param xgyro Angular speed around X axis (raw)
+ * @param ygyro Angular speed around Y axis (raw)
+ * @param zgyro Angular speed around Z axis (raw)
+ * @param xmag X Magnetic field (raw)
+ * @param ymag Y Magnetic field (raw)
+ * @param zmag Z Magnetic field (raw)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, 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)
+{
+	mavlink_message_t msg;
+	mavlink_msg_raw_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RAW_IMU UNPACKING
+
+/**
+ * @brief Get field usec from raw_imu message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field xacc from raw_imu message
+ *
+ * @return X acceleration (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field yacc from raw_imu message
+ *
+ * @return Y acceleration (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field zacc from raw_imu message
+ *
+ * @return Z acceleration (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field xgyro from raw_imu message
+ *
+ * @return Angular speed around X axis (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field ygyro from raw_imu message
+ *
+ * @return Angular speed around Y axis (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field zgyro from raw_imu message
+ *
+ * @return Angular speed around Z axis (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field xmag from raw_imu message
+ *
+ * @return X Magnetic field (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field ymag from raw_imu message
+ *
+ * @return Y Magnetic field (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field zmag from raw_imu message
+ *
+ * @return Z Magnetic field (raw)
+ */
+static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a raw_imu message into a struct
+ *
+ * @param msg The message to decode
+ * @param raw_imu C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
+{
+	raw_imu->usec = mavlink_msg_raw_imu_get_usec(msg);
+	raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg);
+	raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg);
+	raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg);
+	raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg);
+	raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg);
+	raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg);
+	raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg);
+	raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg);
+	raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_raw_pressure.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,190 @@
+// MESSAGE RAW_PRESSURE PACKING
+
+#define MAVLINK_MSG_ID_RAW_PRESSURE 29
+
+typedef struct __mavlink_raw_pressure_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	int16_t press_abs; ///< Absolute pressure (raw)
+	int16_t press_diff1; ///< Differential pressure 1 (raw)
+	int16_t press_diff2; ///< Differential pressure 2 (raw)
+	int16_t temperature; ///< Raw Temperature measurement (raw)
+
+} mavlink_raw_pressure_t;
+
+
+
+/**
+ * @brief Pack a raw_pressure 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (raw)
+ * @param press_diff1 Differential pressure 1 (raw)
+ * @param press_diff2 Differential pressure 2 (raw)
+ * @param temperature Raw Temperature measurement (raw)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
+	i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
+	i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
+	i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a raw_pressure message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (raw)
+ * @param press_diff1 Differential pressure 1 (raw)
+ * @param press_diff2 Differential pressure 2 (raw)
+ * @param temperature Raw Temperature measurement (raw)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
+	i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
+	i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
+	i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a raw_pressure struct into a 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 raw_pressure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
+{
+	return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
+}
+
+/**
+ * @brief Send a raw_pressure message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (raw)
+ * @param press_diff1 Differential pressure 1 (raw)
+ * @param press_diff2 Differential pressure 2 (raw)
+ * @param temperature Raw Temperature measurement (raw)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
+{
+	mavlink_message_t msg;
+	mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RAW_PRESSURE UNPACKING
+
+/**
+ * @brief Get field usec from raw_pressure message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field press_abs from raw_pressure message
+ *
+ * @return Absolute pressure (raw)
+ */
+static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field press_diff1 from raw_pressure message
+ *
+ * @return Differential pressure 1 (raw)
+ */
+static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field press_diff2 from raw_pressure message
+ *
+ * @return Differential pressure 2 (raw)
+ */
+static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field temperature from raw_pressure message
+ *
+ * @return Raw Temperature measurement (raw)
+ */
+static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a raw_pressure message into a struct
+ *
+ * @param msg The message to decode
+ * @param raw_pressure C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
+{
+	raw_pressure->usec = mavlink_msg_raw_pressure_get_usec(msg);
+	raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
+	raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
+	raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
+	raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_override.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,278 @@
+// MESSAGE RC_CHANNELS_OVERRIDE PACKING
+
+#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
+
+typedef struct __mavlink_rc_channels_override_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
+	uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
+	uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
+	uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
+	uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
+	uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
+	uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
+	uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
+
+} mavlink_rc_channels_override_t;
+
+
+
+/**
+ * @brief Pack a rc_channels_override 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 target_system System ID
+ * @param target_component Component ID
+ * @param chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
+	i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
+	i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
+	i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
+	i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
+	i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
+	i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
+	i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a rc_channels_override message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
+	i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
+	i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
+	i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
+	i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
+	i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
+	i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
+	i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a rc_channels_override struct into a 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 rc_channels_override C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
+{
+	return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
+}
+
+/**
+ * @brief Send a rc_channels_override message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_rc_channels_override_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
+
+/**
+ * @brief Get field target_system from rc_channels_override message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from rc_channels_override message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field chan1_raw from rc_channels_override message
+ *
+ * @return RC channel 1 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan2_raw from rc_channels_override message
+ *
+ * @return RC channel 2 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan3_raw from rc_channels_override message
+ *
+ * @return RC channel 3 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan4_raw from rc_channels_override message
+ *
+ * @return RC channel 4 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan5_raw from rc_channels_override message
+ *
+ * @return RC channel 5 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan6_raw from rc_channels_override message
+ *
+ * @return RC channel 6 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan7_raw from rc_channels_override message
+ *
+ * @return RC channel 7 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan8_raw from rc_channels_override message
+ *
+ * @return RC channel 8 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a rc_channels_override message into a struct
+ *
+ * @param msg The message to decode
+ * @param rc_channels_override C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override)
+{
+	rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg);
+	rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg);
+	rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg);
+	rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg);
+	rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg);
+	rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg);
+	rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg);
+	rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg);
+	rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg);
+	rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_raw.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,261 @@
+// MESSAGE RC_CHANNELS_RAW PACKING
+
+#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
+
+typedef struct __mavlink_rc_channels_raw_t 
+{
+	uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
+	uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
+	uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
+	uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
+	uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
+	uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
+	uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
+	uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
+	uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
+
+} mavlink_rc_channels_raw_t;
+
+
+
+/**
+ * @brief Pack a rc_channels_raw 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 chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
+
+	i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
+	i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
+	i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
+	i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
+	i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
+	i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
+	i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
+	i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
+	i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a rc_channels_raw message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
+
+	i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
+	i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
+	i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
+	i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
+	i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
+	i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
+	i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
+	i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
+	i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a rc_channels_raw struct into a 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 rc_channels_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
+{
+	return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
+}
+
+/**
+ * @brief Send a rc_channels_raw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param chan1_raw RC channel 1 value, in microseconds
+ * @param chan2_raw RC channel 2 value, in microseconds
+ * @param chan3_raw RC channel 3 value, in microseconds
+ * @param chan4_raw RC channel 4 value, in microseconds
+ * @param chan5_raw RC channel 5 value, in microseconds
+ * @param chan6_raw RC channel 6 value, in microseconds
+ * @param chan7_raw RC channel 7 value, in microseconds
+ * @param chan8_raw RC channel 8 value, in microseconds
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
+{
+	mavlink_message_t msg;
+	mavlink_msg_rc_channels_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RC_CHANNELS_RAW UNPACKING
+
+/**
+ * @brief Get field chan1_raw from rc_channels_raw message
+ *
+ * @return RC channel 1 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan2_raw from rc_channels_raw message
+ *
+ * @return RC channel 2 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan3_raw from rc_channels_raw message
+ *
+ * @return RC channel 3 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan4_raw from rc_channels_raw message
+ *
+ * @return RC channel 4 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan5_raw from rc_channels_raw message
+ *
+ * @return RC channel 5 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan6_raw from rc_channels_raw message
+ *
+ * @return RC channel 6 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan7_raw from rc_channels_raw message
+ *
+ * @return RC channel 7 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field chan8_raw from rc_channels_raw message
+ *
+ * @return RC channel 8 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field rssi from rc_channels_raw message
+ *
+ * @return Receive signal strength indicator, 0: 0%, 255: 100%
+ */
+static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Decode a rc_channels_raw message into a struct
+ *
+ * @param msg The message to decode
+ * @param rc_channels_raw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
+{
+	rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
+	rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
+	rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
+	rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
+	rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
+	rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
+	rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
+	rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
+	rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_rc_channels_scaled.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,261 @@
+// MESSAGE RC_CHANNELS_SCALED PACKING
+
+#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 36
+
+typedef struct __mavlink_rc_channels_scaled_t 
+{
+	int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
+
+} mavlink_rc_channels_scaled_t;
+
+
+
+/**
+ * @brief Pack a rc_channels_scaled 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 chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
+
+	i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a rc_channels_scaled message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
+
+	i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+	i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a rc_channels_scaled struct into a 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 rc_channels_scaled C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
+{
+	return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
+}
+
+/**
+ * @brief Send a rc_channels_scaled message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
+{
+	mavlink_message_t msg;
+	mavlink_msg_rc_channels_scaled_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RC_CHANNELS_SCALED UNPACKING
+
+/**
+ * @brief Get field chan1_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan2_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan3_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan4_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan5_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan6_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan7_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field chan8_scaled from rc_channels_scaled message
+ *
+ * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ */
+static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field rssi from rc_channels_scaled message
+ *
+ * @return Receive signal strength indicator, 0: 0%, 255: 100%
+ */
+static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+}
+
+/**
+ * @brief Decode a rc_channels_scaled message into a struct
+ *
+ * @param msg The message to decode
+ * @param rc_channels_scaled C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled)
+{
+	rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg);
+	rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg);
+	rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg);
+	rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg);
+	rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg);
+	rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg);
+	rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg);
+	rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg);
+	rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_request_data_stream.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,172 @@
+// MESSAGE REQUEST_DATA_STREAM PACKING
+
+#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
+
+typedef struct __mavlink_request_data_stream_t 
+{
+	uint8_t target_system; ///< The target requested to send the message stream.
+	uint8_t target_component; ///< The target requested to send the message stream.
+	uint8_t req_stream_id; ///< The ID of the requested message type
+	uint16_t req_message_rate; ///< Update rate in Hertz
+	uint8_t start_stop; ///< 1 to start sending, 0 to stop sending.
+
+} mavlink_request_data_stream_t;
+
+
+
+/**
+ * @brief Pack a request_data_stream 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 target_system The target requested to send the message stream.
+ * @param target_component The target requested to send the message stream.
+ * @param req_stream_id The ID of the requested message type
+ * @param req_message_rate Update rate in Hertz
+ * @param start_stop 1 to start sending, 0 to stop sending.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // The target requested to send the message stream.
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // The target requested to send the message stream.
+	i += put_uint8_t_by_index(req_stream_id, i, msg->payload); // The ID of the requested message type
+	i += put_uint16_t_by_index(req_message_rate, i, msg->payload); // Update rate in Hertz
+	i += put_uint8_t_by_index(start_stop, i, msg->payload); // 1 to start sending, 0 to stop sending.
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a request_data_stream message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system The target requested to send the message stream.
+ * @param target_component The target requested to send the message stream.
+ * @param req_stream_id The ID of the requested message type
+ * @param req_message_rate Update rate in Hertz
+ * @param start_stop 1 to start sending, 0 to stop sending.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // The target requested to send the message stream.
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // The target requested to send the message stream.
+	i += put_uint8_t_by_index(req_stream_id, i, msg->payload); // The ID of the requested message type
+	i += put_uint16_t_by_index(req_message_rate, i, msg->payload); // Update rate in Hertz
+	i += put_uint8_t_by_index(start_stop, i, msg->payload); // 1 to start sending, 0 to stop sending.
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a request_data_stream struct into a 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 request_data_stream C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
+{
+	return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
+}
+
+/**
+ * @brief Send a request_data_stream message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system The target requested to send the message stream.
+ * @param target_component The target requested to send the message stream.
+ * @param req_stream_id The ID of the requested message type
+ * @param req_message_rate Update rate in Hertz
+ * @param start_stop 1 to start sending, 0 to stop sending.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
+{
+	mavlink_message_t msg;
+	mavlink_msg_request_data_stream_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE REQUEST_DATA_STREAM UNPACKING
+
+/**
+ * @brief Get field target_system from request_data_stream message
+ *
+ * @return The target requested to send the message stream.
+ */
+static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from request_data_stream message
+ *
+ * @return The target requested to send the message stream.
+ */
+static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field req_stream_id from request_data_stream message
+ *
+ * @return The ID of the requested message type
+ */
+static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field req_message_rate from request_data_stream message
+ *
+ * @return Update rate in Hertz
+ */
+static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field start_stop from request_data_stream message
+ *
+ * @return 1 to start sending, 0 to stop sending.
+ */
+static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Decode a request_data_stream message into a struct
+ *
+ * @param msg The message to decode
+ * @param request_data_stream C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
+{
+	request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
+	request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
+	request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
+	request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
+	request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,198 @@
+// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING
+
+#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 58
+
+typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t 
+{
+	uint64_t time_us; ///< Timestamp in micro seconds since unix epoch
+	float roll_speed; ///< Desired roll angular speed in rad/s
+	float pitch_speed; ///< Desired pitch angular speed in rad/s
+	float yaw_speed; ///< Desired yaw angular speed in rad/s
+	float thrust; ///< Collective thrust, normalized to 0 .. 1
+
+} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t;
+
+
+
+/**
+ * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint 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_us Timestamp in micro seconds since unix epoch
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_us, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp in micro seconds since unix epoch
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_us Timestamp in micro seconds since unix epoch
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_us, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp in micro seconds since unix epoch
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a 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 roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
+{
+	return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_us, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
+}
+
+/**
+ * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_us Timestamp in micro seconds since unix epoch
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint64_t time_us, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	mavlink_message_t msg;
+	mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_us, roll_speed, pitch_speed, yaw_speed, thrust);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING
+
+/**
+ * @brief Get field time_us from roll_pitch_yaw_speed_thrust_setpoint message
+ *
+ * @return Timestamp in micro seconds since unix epoch
+ */
+static inline uint64_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_us(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message
+ *
+ * @return Desired roll angular speed in rad/s
+ */
+static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message
+ *
+ * @return Desired pitch angular speed in rad/s
+ */
+static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message
+ *
+ * @return Desired yaw angular speed in rad/s
+ */
+static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message
+ *
+ * @return Collective thrust, normalized to 0 .. 1
+ */
+static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct
+ *
+ * @param msg The message to decode
+ * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
+{
+	roll_pitch_yaw_speed_thrust_setpoint->time_us = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_us(msg);
+	roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg);
+	roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg);
+	roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg);
+	roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,198 @@
+// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING
+
+#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 57
+
+typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t 
+{
+	uint64_t time_us; ///< Timestamp in micro seconds since unix epoch
+	float roll; ///< Desired roll angle in radians
+	float pitch; ///< Desired pitch angle in radians
+	float yaw; ///< Desired yaw angle in radians
+	float thrust; ///< Collective thrust, normalized to 0 .. 1
+
+} mavlink_roll_pitch_yaw_thrust_setpoint_t;
+
+
+
+/**
+ * @brief Pack a roll_pitch_yaw_thrust_setpoint 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_us Timestamp in micro seconds since unix epoch
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_us, float roll, float pitch, float yaw, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp in micro seconds since unix epoch
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a roll_pitch_yaw_thrust_setpoint message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_us Timestamp in micro seconds since unix epoch
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_us, float roll, float pitch, float yaw, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
+
+	i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp in micro seconds since unix epoch
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a 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 roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
+{
+	return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_us, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
+}
+
+/**
+ * @brief Send a roll_pitch_yaw_thrust_setpoint message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_us Timestamp in micro seconds since unix epoch
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint64_t time_us, float roll, float pitch, float yaw, float thrust)
+{
+	mavlink_message_t msg;
+	mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_us, roll, pitch, yaw, thrust);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING
+
+/**
+ * @brief Get field time_us from roll_pitch_yaw_thrust_setpoint message
+ *
+ * @return Timestamp in micro seconds since unix epoch
+ */
+static inline uint64_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_us(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field roll from roll_pitch_yaw_thrust_setpoint message
+ *
+ * @return Desired roll angle in radians
+ */
+static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message
+ *
+ * @return Desired pitch angle in radians
+ */
+static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message
+ *
+ * @return Desired yaw angle in radians
+ */
+static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message
+ *
+ * @return Collective thrust, normalized to 0 .. 1
+ */
+static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct
+ *
+ * @param msg The message to decode
+ * @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
+{
+	roll_pitch_yaw_thrust_setpoint->time_us = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_us(msg);
+	roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg);
+	roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg);
+	roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg);
+	roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_safety_allowed_area.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,233 @@
+// MESSAGE SAFETY_ALLOWED_AREA PACKING
+
+#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 54
+
+typedef struct __mavlink_safety_allowed_area_t 
+{
+	uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	float p1x; ///< x position 1 / Latitude 1
+	float p1y; ///< y position 1 / Longitude 1
+	float p1z; ///< z position 1 / Altitude 1
+	float p2x; ///< x position 2 / Latitude 2
+	float p2y; ///< y position 2 / Longitude 2
+	float p2z; ///< z position 2 / Altitude 2
+
+} mavlink_safety_allowed_area_t;
+
+
+
+/**
+ * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
+
+	i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1
+	i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1
+	i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1
+	i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2
+	i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2
+	i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a safety_allowed_area message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
+
+	i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1
+	i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1
+	i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1
+	i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2
+	i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2
+	i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a safety_allowed_area struct into a 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 safety_allowed_area C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area)
+{
+	return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z);
+}
+
+/**
+ * @brief Send a safety_allowed_area message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_safety_allowed_area_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, frame, p1x, p1y, p1z, p2x, p2y, p2z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SAFETY_ALLOWED_AREA UNPACKING
+
+/**
+ * @brief Get field frame from safety_allowed_area message
+ *
+ * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ */
+static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field p1x from safety_allowed_area message
+ *
+ * @return x position 1 / Latitude 1
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p1y from safety_allowed_area message
+ *
+ * @return y position 1 / Longitude 1
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p1z from safety_allowed_area message
+ *
+ * @return z position 1 / Altitude 1
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2x from safety_allowed_area message
+ *
+ * @return x position 2 / Latitude 2
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2y from safety_allowed_area message
+ *
+ * @return y position 2 / Longitude 2
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2z from safety_allowed_area message
+ *
+ * @return z position 2 / Altitude 2
+ */
+static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a safety_allowed_area message into a struct
+ *
+ * @param msg The message to decode
+ * @param safety_allowed_area C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area)
+{
+	safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg);
+	safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg);
+	safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg);
+	safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg);
+	safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg);
+	safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg);
+	safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_safety_set_allowed_area.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,267 @@
+// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING
+
+#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 53
+
+typedef struct __mavlink_safety_set_allowed_area_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	float p1x; ///< x position 1 / Latitude 1
+	float p1y; ///< y position 1 / Longitude 1
+	float p1z; ///< z position 1 / Altitude 1
+	float p2x; ///< x position 2 / Latitude 2
+	float p2y; ///< y position 2 / Longitude 2
+	float p2z; ///< z position 2 / Altitude 2
+
+} mavlink_safety_set_allowed_area_t;
+
+
+
+/**
+ * @brief Pack a safety_set_allowed_area 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 target_system System ID
+ * @param target_component Component ID
+ * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1
+	i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1
+	i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1
+	i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2
+	i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2
+	i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a safety_set_allowed_area message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+	i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1
+	i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1
+	i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1
+	i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2
+	i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2
+	i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a safety_set_allowed_area struct into a 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 safety_set_allowed_area C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
+{
+	return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
+}
+
+/**
+ * @brief Send a safety_set_allowed_area message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ * @param p1x x position 1 / Latitude 1
+ * @param p1y y position 1 / Longitude 1
+ * @param p1z z position 1 / Altitude 1
+ * @param p2x x position 2 / Latitude 2
+ * @param p2y y position 2 / Longitude 2
+ * @param p2z z position 2 / Altitude 2
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_safety_set_allowed_area_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING
+
+/**
+ * @brief Get field target_system from safety_set_allowed_area message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from safety_set_allowed_area message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field frame from safety_set_allowed_area message
+ *
+ * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
+ */
+static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field p1x from safety_set_allowed_area message
+ *
+ * @return x position 1 / Latitude 1
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p1y from safety_set_allowed_area message
+ *
+ * @return y position 1 / Longitude 1
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p1z from safety_set_allowed_area message
+ *
+ * @return z position 1 / Altitude 1
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2x from safety_set_allowed_area message
+ *
+ * @return x position 2 / Latitude 2
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2y from safety_set_allowed_area message
+ *
+ * @return y position 2 / Longitude 2
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field p2z from safety_set_allowed_area message
+ *
+ * @return z position 2 / Altitude 2
+ */
+static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a safety_set_allowed_area message into a struct
+ *
+ * @param msg The message to decode
+ * @param safety_set_allowed_area C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
+{
+	safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg);
+	safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg);
+	safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg);
+	safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg);
+	safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg);
+	safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg);
+	safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg);
+	safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg);
+	safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_scaled_imu.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,290 @@
+// MESSAGE SCALED_IMU PACKING
+
+#define MAVLINK_MSG_ID_SCALED_IMU 26
+
+typedef struct __mavlink_scaled_imu_t 
+{
+    uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds 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;
+
+
+
+/**
+ * @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 usec Timestamp (microseconds since UNIX epoch or microseconds 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, uint64_t usec, 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)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+    i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+    i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+    i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
+    i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
+    i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
+    i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
+    i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
+    i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds 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, uint64_t usec, 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)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+    i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
+    i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
+    i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
+    i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
+    i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
+    i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
+    i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
+    i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
+    i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a scaled_imu struct into a 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 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->usec, 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 usec Timestamp (microseconds since UNIX epoch or microseconds 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, uint64_t usec, 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)
+{
+    mavlink_message_t msg;
+    mavlink_msg_scaled_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SCALED_IMU UNPACKING
+
+/**
+ * @brief Get field usec from scaled_imu message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_scaled_imu_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    scaled_imu->usec = mavlink_msg_scaled_imu_get_usec(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);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_scaled_pressure.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,174 @@
+// MESSAGE SCALED_PRESSURE PACKING
+
+#define MAVLINK_MSG_ID_SCALED_PRESSURE 38
+
+typedef struct __mavlink_scaled_pressure_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	float press_abs; ///< Absolute pressure (hectopascal)
+	float press_diff; ///< Differential pressure 1 (hectopascal)
+	int16_t temperature; ///< Temperature measurement (0.01 degrees celsius)
+
+} mavlink_scaled_pressure_t;
+
+
+
+/**
+ * @brief Pack a scaled_pressure 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (hectopascal)
+ * @param press_diff Differential pressure 1 (hectopascal)
+ * @param temperature Temperature measurement (0.01 degrees celsius)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff, int16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
+	i += put_float_by_index(press_diff, i, msg->payload); // Differential pressure 1 (hectopascal)
+	i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a scaled_pressure message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (hectopascal)
+ * @param press_diff Differential pressure 1 (hectopascal)
+ * @param temperature Temperature measurement (0.01 degrees celsius)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff, int16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+	i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
+	i += put_float_by_index(press_diff, i, msg->payload); // Differential pressure 1 (hectopascal)
+	i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a scaled_pressure struct into a 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 scaled_pressure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
+{
+	return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->usec, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
+}
+
+/**
+ * @brief Send a scaled_pressure message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ * @param press_abs Absolute pressure (hectopascal)
+ * @param press_diff Differential pressure 1 (hectopascal)
+ * @param temperature Temperature measurement (0.01 degrees celsius)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff, int16_t temperature)
+{
+	mavlink_message_t msg;
+	mavlink_msg_scaled_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff, temperature);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SCALED_PRESSURE UNPACKING
+
+/**
+ * @brief Get field usec from scaled_pressure message
+ *
+ * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ */
+static inline uint64_t mavlink_msg_scaled_pressure_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field press_abs from scaled_pressure message
+ *
+ * @return Absolute pressure (hectopascal)
+ */
+static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field press_diff from scaled_pressure message
+ *
+ * @return Differential pressure 1 (hectopascal)
+ */
+static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field temperature from scaled_pressure message
+ *
+ * @return Temperature measurement (0.01 degrees celsius)
+ */
+static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a scaled_pressure message into a struct
+ *
+ * @param msg The message to decode
+ * @param scaled_pressure C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
+{
+	scaled_pressure->usec = mavlink_msg_scaled_pressure_get_usec(msg);
+	scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
+	scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
+	scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_servo_output_raw.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,244 @@
+// MESSAGE SERVO_OUTPUT_RAW PACKING
+
+#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 37
+
+typedef struct __mavlink_servo_output_raw_t 
+{
+	uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
+	uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
+	uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
+	uint16_t servo4_raw; ///< Servo output 4 value, in microseconds
+	uint16_t servo5_raw; ///< Servo output 5 value, in microseconds
+	uint16_t servo6_raw; ///< Servo output 6 value, in microseconds
+	uint16_t servo7_raw; ///< Servo output 7 value, in microseconds
+	uint16_t servo8_raw; ///< Servo output 8 value, in microseconds
+
+} mavlink_servo_output_raw_t;
+
+
+
+/**
+ * @brief Pack a servo_output_raw 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 servo1_raw Servo output 1 value, in microseconds
+ * @param servo2_raw Servo output 2 value, in microseconds
+ * @param servo3_raw Servo output 3 value, in microseconds
+ * @param servo4_raw Servo output 4 value, in microseconds
+ * @param servo5_raw Servo output 5 value, in microseconds
+ * @param servo6_raw Servo output 6 value, in microseconds
+ * @param servo7_raw Servo output 7 value, in microseconds
+ * @param servo8_raw Servo output 8 value, in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
+
+	i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds
+	i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds
+	i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds
+	i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds
+	i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds
+	i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds
+	i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds
+	i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a servo_output_raw message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param servo1_raw Servo output 1 value, in microseconds
+ * @param servo2_raw Servo output 2 value, in microseconds
+ * @param servo3_raw Servo output 3 value, in microseconds
+ * @param servo4_raw Servo output 4 value, in microseconds
+ * @param servo5_raw Servo output 5 value, in microseconds
+ * @param servo6_raw Servo output 6 value, in microseconds
+ * @param servo7_raw Servo output 7 value, in microseconds
+ * @param servo8_raw Servo output 8 value, in microseconds
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
+
+	i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds
+	i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds
+	i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds
+	i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds
+	i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds
+	i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds
+	i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds
+	i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a servo_output_raw struct into a 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 servo_output_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
+{
+	return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
+}
+
+/**
+ * @brief Send a servo_output_raw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param servo1_raw Servo output 1 value, in microseconds
+ * @param servo2_raw Servo output 2 value, in microseconds
+ * @param servo3_raw Servo output 3 value, in microseconds
+ * @param servo4_raw Servo output 4 value, in microseconds
+ * @param servo5_raw Servo output 5 value, in microseconds
+ * @param servo6_raw Servo output 6 value, in microseconds
+ * @param servo7_raw Servo output 7 value, in microseconds
+ * @param servo8_raw Servo output 8 value, in microseconds
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_servo_output_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SERVO_OUTPUT_RAW UNPACKING
+
+/**
+ * @brief Get field servo1_raw from servo_output_raw message
+ *
+ * @return Servo output 1 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo2_raw from servo_output_raw message
+ *
+ * @return Servo output 2 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo3_raw from servo_output_raw message
+ *
+ * @return Servo output 3 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo4_raw from servo_output_raw message
+ *
+ * @return Servo output 4 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo5_raw from servo_output_raw message
+ *
+ * @return Servo output 5 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo6_raw from servo_output_raw message
+ *
+ * @return Servo output 6 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo7_raw from servo_output_raw message
+ *
+ * @return Servo output 7 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field servo8_raw from servo_output_raw message
+ *
+ * @return Servo output 8 value, in microseconds
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a servo_output_raw message into a struct
+ *
+ * @param msg The message to decode
+ * @param servo_output_raw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
+{
+	servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
+	servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
+	servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);
+	servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg);
+	servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg);
+	servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg);
+	servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg);
+	servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_altitude.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,123 @@
+// MESSAGE SET_ALTITUDE PACKING
+
+#define MAVLINK_MSG_ID_SET_ALTITUDE 65
+
+typedef struct __mavlink_set_altitude_t 
+{
+	uint8_t target; ///< The system setting the altitude
+	uint32_t mode; ///< The new altitude in meters
+
+} mavlink_set_altitude_t;
+
+
+
+/**
+ * @brief Pack a set_altitude 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 target The system setting the altitude
+ * @param mode The new altitude in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint32_t mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the altitude
+	i += put_uint32_t_by_index(mode, i, msg->payload); // The new altitude in meters
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_altitude message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system setting the altitude
+ * @param mode The new altitude in meters
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint32_t mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the altitude
+	i += put_uint32_t_by_index(mode, i, msg->payload); // The new altitude in meters
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_altitude struct into a 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 set_altitude C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude)
+{
+	return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode);
+}
+
+/**
+ * @brief Send a set_altitude message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system setting the altitude
+ * @param mode The new altitude in meters
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_altitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_ALTITUDE UNPACKING
+
+/**
+ * @brief Get field target from set_altitude message
+ *
+ * @return The system setting the altitude
+ */
+static inline uint8_t mavlink_msg_set_altitude_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field mode from set_altitude message
+ *
+ * @return The new altitude in meters
+ */
+static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Decode a set_altitude message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_altitude C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude)
+{
+	set_altitude->target = mavlink_msg_set_altitude_get_target(msg);
+	set_altitude->mode = mavlink_msg_set_altitude_get_mode(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_mode.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE SET_MODE PACKING
+
+#define MAVLINK_MSG_ID_SET_MODE 11
+
+typedef struct __mavlink_set_mode_t 
+{
+	uint8_t target; ///< The system setting the mode
+	uint8_t mode; ///< The new mode
+
+} mavlink_set_mode_t;
+
+
+
+/**
+ * @brief Pack a set_mode 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 target The system setting the mode
+ * @param mode The new mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_MODE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
+	i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_mode message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system setting the mode
+ * @param mode The new mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_MODE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
+	i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_mode struct into a 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 set_mode C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
+{
+	return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode);
+}
+
+/**
+ * @brief Send a set_mode message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system setting the mode
+ * @param mode The new mode
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_MODE UNPACKING
+
+/**
+ * @brief Get field target from set_mode message
+ *
+ * @return The system setting the mode
+ */
+static inline uint8_t mavlink_msg_set_mode_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field mode from set_mode message
+ *
+ * @return The new mode
+ */
+static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a set_mode message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_mode C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
+{
+	set_mode->target = mavlink_msg_set_mode_get_target(msg);
+	set_mode->mode = mavlink_msg_set_mode_get_mode(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_nav_mode.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE SET_NAV_MODE PACKING
+
+#define MAVLINK_MSG_ID_SET_NAV_MODE 12
+
+typedef struct __mavlink_set_nav_mode_t 
+{
+	uint8_t target; ///< The system setting the mode
+	uint8_t nav_mode; ///< The new navigation mode
+
+} mavlink_set_nav_mode_t;
+
+
+
+/**
+ * @brief Pack a set_nav_mode 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 target The system setting the mode
+ * @param nav_mode The new navigation mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_nav_mode message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system setting the mode
+ * @param nav_mode The new navigation mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_nav_mode struct into a 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 set_nav_mode C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode)
+{
+	return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode);
+}
+
+/**
+ * @brief Send a set_nav_mode message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system setting the mode
+ * @param nav_mode The new navigation mode
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_nav_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, nav_mode);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_NAV_MODE UNPACKING
+
+/**
+ * @brief Get field target from set_nav_mode message
+ *
+ * @return The system setting the mode
+ */
+static inline uint8_t mavlink_msg_set_nav_mode_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field nav_mode from set_nav_mode message
+ *
+ * @return The new navigation mode
+ */
+static inline uint8_t mavlink_msg_set_nav_mode_get_nav_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a set_nav_mode message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_nav_mode C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_nav_mode_decode(const mavlink_message_t* msg, mavlink_set_nav_mode_t* set_nav_mode)
+{
+	set_nav_mode->target = mavlink_msg_set_nav_mode_get_target(msg);
+	set_nav_mode->nav_mode = mavlink_msg_set_nav_mode_get_nav_mode(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,184 @@
+// MESSAGE SET_ROLL_PITCH_YAW PACKING
+
+#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW 55
+
+typedef struct __mavlink_set_roll_pitch_yaw_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float roll; ///< Desired roll angle in radians
+	float pitch; ///< Desired pitch angle in radians
+	float yaw; ///< Desired yaw angle in radians
+
+} mavlink_set_roll_pitch_yaw_t;
+
+
+
+/**
+ * @brief Pack a set_roll_pitch_yaw 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 target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_roll_pitch_yaw message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_roll_pitch_yaw struct into a 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 set_roll_pitch_yaw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_t* set_roll_pitch_yaw)
+{
+	return mavlink_msg_set_roll_pitch_yaw_pack(system_id, component_id, msg, set_roll_pitch_yaw->target_system, set_roll_pitch_yaw->target_component, set_roll_pitch_yaw->roll, set_roll_pitch_yaw->pitch, set_roll_pitch_yaw->yaw);
+}
+
+/**
+ * @brief Send a set_roll_pitch_yaw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_roll_pitch_yaw_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_roll_pitch_yaw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll, pitch, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_ROLL_PITCH_YAW UNPACKING
+
+/**
+ * @brief Get field target_system from set_roll_pitch_yaw message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from set_roll_pitch_yaw message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field roll from set_roll_pitch_yaw message
+ *
+ * @return Desired roll angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from set_roll_pitch_yaw message
+ *
+ * @return Desired pitch angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from set_roll_pitch_yaw message
+ *
+ * @return Desired yaw angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a set_roll_pitch_yaw message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_roll_pitch_yaw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_t* set_roll_pitch_yaw)
+{
+	set_roll_pitch_yaw->target_system = mavlink_msg_set_roll_pitch_yaw_get_target_system(msg);
+	set_roll_pitch_yaw->target_component = mavlink_msg_set_roll_pitch_yaw_get_target_component(msg);
+	set_roll_pitch_yaw->roll = mavlink_msg_set_roll_pitch_yaw_get_roll(msg);
+	set_roll_pitch_yaw->pitch = mavlink_msg_set_roll_pitch_yaw_get_pitch(msg);
+	set_roll_pitch_yaw->yaw = mavlink_msg_set_roll_pitch_yaw_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,184 @@
+// MESSAGE SET_ROLL_PITCH_YAW_SPEED PACKING
+
+#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED 56
+
+typedef struct __mavlink_set_roll_pitch_yaw_speed_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float roll_speed; ///< Desired roll angular speed in rad/s
+	float pitch_speed; ///< Desired pitch angular speed in rad/s
+	float yaw_speed; ///< Desired yaw angular speed in rad/s
+
+} mavlink_set_roll_pitch_yaw_speed_t;
+
+
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_speed 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 target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_speed message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_roll_pitch_yaw_speed struct into a 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 set_roll_pitch_yaw_speed C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_t* set_roll_pitch_yaw_speed)
+{
+	return mavlink_msg_set_roll_pitch_yaw_speed_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed->target_system, set_roll_pitch_yaw_speed->target_component, set_roll_pitch_yaw_speed->roll_speed, set_roll_pitch_yaw_speed->pitch_speed, set_roll_pitch_yaw_speed->yaw_speed);
+}
+
+/**
+ * @brief Send a set_roll_pitch_yaw_speed message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_roll_pitch_yaw_speed_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_roll_pitch_yaw_speed_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll_speed, pitch_speed, yaw_speed);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_ROLL_PITCH_YAW_SPEED UNPACKING
+
+/**
+ * @brief Get field target_system from set_roll_pitch_yaw_speed message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from set_roll_pitch_yaw_speed message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field roll_speed from set_roll_pitch_yaw_speed message
+ *
+ * @return Desired roll angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_roll_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch_speed from set_roll_pitch_yaw_speed message
+ *
+ * @return Desired pitch angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_pitch_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw_speed from set_roll_pitch_yaw_speed message
+ *
+ * @return Desired yaw angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_yaw_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a set_roll_pitch_yaw_speed message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_roll_pitch_yaw_speed C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_speed_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_t* set_roll_pitch_yaw_speed)
+{
+	set_roll_pitch_yaw_speed->target_system = mavlink_msg_set_roll_pitch_yaw_speed_get_target_system(msg);
+	set_roll_pitch_yaw_speed->target_component = mavlink_msg_set_roll_pitch_yaw_speed_get_target_component(msg);
+	set_roll_pitch_yaw_speed->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_roll_speed(msg);
+	set_roll_pitch_yaw_speed->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_pitch_speed(msg);
+	set_roll_pitch_yaw_speed->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_yaw_speed(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,206 @@
+// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING
+
+#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 56
+
+typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float roll_speed; ///< Desired roll angular speed in rad/s
+	float pitch_speed; ///< Desired pitch angular speed in rad/s
+	float yaw_speed; ///< Desired yaw angular speed in rad/s
+	float thrust; ///< Collective thrust, normalized to 0 .. 1
+
+} mavlink_set_roll_pitch_yaw_speed_thrust_t;
+
+
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_speed_thrust 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 target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_speed_thrust message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
+	i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
+	i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_roll_pitch_yaw_speed_thrust struct into a 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 set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
+{
+	return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
+}
+
+/**
+ * @brief Send a set_roll_pitch_yaw_speed_thrust message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll_speed Desired roll angular speed in rad/s
+ * @param pitch_speed Desired pitch angular speed in rad/s
+ * @param yaw_speed Desired yaw angular speed in rad/s
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING
+
+/**
+ * @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return Desired roll angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return Desired pitch angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return Desired yaw angular speed in rad/s
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message
+ *
+ * @return Collective thrust, normalized to 0 .. 1
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
+{
+	set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg);
+	set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg);
+	set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg);
+	set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg);
+	set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg);
+	set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,206 @@
+// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING
+
+#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 55
+
+typedef struct __mavlink_set_roll_pitch_yaw_thrust_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float roll; ///< Desired roll angle in radians
+	float pitch; ///< Desired pitch angle in radians
+	float yaw; ///< Desired yaw angle in radians
+	float thrust; ///< Collective thrust, normalized to 0 .. 1
+
+} mavlink_set_roll_pitch_yaw_thrust_t;
+
+
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_thrust 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 target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_roll_pitch_yaw_thrust message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
+	i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
+	i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
+	i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_roll_pitch_yaw_thrust struct into a 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 set_roll_pitch_yaw_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
+{
+	return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
+}
+
+/**
+ * @brief Send a set_roll_pitch_yaw_thrust message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param roll Desired roll angle in radians
+ * @param pitch Desired pitch angle in radians
+ * @param yaw Desired yaw angle in radians
+ * @param thrust Collective thrust, normalized to 0 .. 1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll, pitch, yaw, thrust);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING
+
+/**
+ * @brief Get field target_system from set_roll_pitch_yaw_thrust message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from set_roll_pitch_yaw_thrust message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field roll from set_roll_pitch_yaw_thrust message
+ *
+ * @return Desired roll angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from set_roll_pitch_yaw_thrust message
+ *
+ * @return Desired pitch angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from set_roll_pitch_yaw_thrust message
+ *
+ * @return Desired yaw angle in radians
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from set_roll_pitch_yaw_thrust message
+ *
+ * @return Collective thrust, normalized to 0 .. 1
+ */
+static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a set_roll_pitch_yaw_thrust message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
+{
+	set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg);
+	set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg);
+	set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg);
+	set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg);
+	set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg);
+	set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_state_correction.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,282 @@
+// MESSAGE STATE_CORRECTION PACKING
+
+#define MAVLINK_MSG_ID_STATE_CORRECTION 64
+
+typedef struct __mavlink_state_correction_t 
+{
+	float xErr; ///< x position error
+	float yErr; ///< y position error
+	float zErr; ///< z position error
+	float rollErr; ///< roll error (radians)
+	float pitchErr; ///< pitch error (radians)
+	float yawErr; ///< yaw error (radians)
+	float vxErr; ///< x velocity
+	float vyErr; ///< y velocity
+	float vzErr; ///< z velocity
+
+} mavlink_state_correction_t;
+
+
+
+/**
+ * @brief Pack a state_correction 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 xErr x position error
+ * @param yErr y position error
+ * @param zErr z position error
+ * @param rollErr roll error (radians)
+ * @param pitchErr pitch error (radians)
+ * @param yawErr yaw error (radians)
+ * @param vxErr x velocity
+ * @param vyErr y velocity
+ * @param vzErr z velocity
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
+
+	i += put_float_by_index(xErr, i, msg->payload); // x position error
+	i += put_float_by_index(yErr, i, msg->payload); // y position error
+	i += put_float_by_index(zErr, i, msg->payload); // z position error
+	i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
+	i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
+	i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
+	i += put_float_by_index(vxErr, i, msg->payload); // x velocity
+	i += put_float_by_index(vyErr, i, msg->payload); // y velocity
+	i += put_float_by_index(vzErr, i, msg->payload); // z velocity
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a state_correction message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param xErr x position error
+ * @param yErr y position error
+ * @param zErr z position error
+ * @param rollErr roll error (radians)
+ * @param pitchErr pitch error (radians)
+ * @param yawErr yaw error (radians)
+ * @param vxErr x velocity
+ * @param vyErr y velocity
+ * @param vzErr z velocity
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
+
+	i += put_float_by_index(xErr, i, msg->payload); // x position error
+	i += put_float_by_index(yErr, i, msg->payload); // y position error
+	i += put_float_by_index(zErr, i, msg->payload); // z position error
+	i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
+	i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
+	i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
+	i += put_float_by_index(vxErr, i, msg->payload); // x velocity
+	i += put_float_by_index(vyErr, i, msg->payload); // y velocity
+	i += put_float_by_index(vzErr, i, msg->payload); // z velocity
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a state_correction struct into a 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 state_correction C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
+{
+	return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
+}
+
+/**
+ * @brief Send a state_correction message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param xErr x position error
+ * @param yErr y position error
+ * @param zErr z position error
+ * @param rollErr roll error (radians)
+ * @param pitchErr pitch error (radians)
+ * @param yawErr yaw error (radians)
+ * @param vxErr x velocity
+ * @param vyErr y velocity
+ * @param vzErr z velocity
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
+{
+	mavlink_message_t msg;
+	mavlink_msg_state_correction_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE STATE_CORRECTION UNPACKING
+
+/**
+ * @brief Get field xErr from state_correction message
+ *
+ * @return x position error
+ */
+static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yErr from state_correction message
+ *
+ * @return y position error
+ */
+static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field zErr from state_correction message
+ *
+ * @return z position error
+ */
+static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field rollErr from state_correction message
+ *
+ * @return roll error (radians)
+ */
+static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitchErr from state_correction message
+ *
+ * @return pitch error (radians)
+ */
+static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yawErr from state_correction message
+ *
+ * @return yaw error (radians)
+ */
+static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field vxErr from state_correction message
+ *
+ * @return x velocity
+ */
+static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field vyErr from state_correction message
+ *
+ * @return y velocity
+ */
+static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field vzErr from state_correction message
+ *
+ * @return z velocity
+ */
+static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a state_correction message into a struct
+ *
+ * @param msg The message to decode
+ * @param state_correction C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction)
+{
+	state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg);
+	state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg);
+	state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg);
+	state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg);
+	state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg);
+	state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg);
+	state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg);
+	state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg);
+	state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_statustext.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,121 @@
+// MESSAGE STATUSTEXT PACKING
+
+#define MAVLINK_MSG_ID_STATUSTEXT 254
+
+typedef struct __mavlink_statustext_t 
+{
+	uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault
+	int8_t text[50]; ///< Status text message, without null termination character
+
+} mavlink_statustext_t;
+
+#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
+
+
+/**
+ * @brief Pack a statustext 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 severity Severity of status, 0 = info message, 255 = critical fault
+ * @param text Status text message, without null termination character
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t severity, const int8_t* text)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
+
+	i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault
+	i += put_array_by_index((const int8_t*)text, sizeof(int8_t)*50, i, msg->payload); // Status text message, without null termination character
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a statustext message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param severity Severity of status, 0 = info message, 255 = critical fault
+ * @param text Status text message, without null termination character
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t severity, const int8_t* text)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
+
+	i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault
+	i += put_array_by_index((const int8_t*)text, sizeof(int8_t)*50, i, msg->payload); // Status text message, without null termination character
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a statustext struct into a 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 statustext C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
+{
+	return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
+}
+
+/**
+ * @brief Send a statustext message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param severity Severity of status, 0 = info message, 255 = critical fault
+ * @param text Status text message, without null termination character
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text)
+{
+	mavlink_message_t msg;
+	mavlink_msg_statustext_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, severity, text);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE STATUSTEXT UNPACKING
+
+/**
+ * @brief Get field severity from statustext message
+ *
+ * @return Severity of status, 0 = info message, 255 = critical fault
+ */
+static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field text from statustext message
+ *
+ * @return Status text message, without null termination character
+ */
+static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t), sizeof(int8_t)*50);
+	return sizeof(int8_t)*50;
+}
+
+/**
+ * @brief Decode a statustext message into a struct
+ *
+ * @param msg The message to decode
+ * @param statustext C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
+{
+	statustext->severity = mavlink_msg_statustext_get_severity(msg);
+	mavlink_msg_statustext_get_text(msg, statustext->text);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_sys_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,215 @@
+// MESSAGE SYS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_SYS_STATUS 34
+
+typedef struct __mavlink_sys_status_t 
+{
+    uint8_t mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+    uint8_t nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM
+    uint8_t status; ///< System status flag, see MAV_STATUS ENUM
+    uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+    uint16_t vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt)
+    uint16_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000)
+    uint16_t packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV)
+
+} mavlink_sys_status_t;
+
+
+
+/**
+ * @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 mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+ * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
+ * @param status System status flag, see MAV_STATUS ENUM
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
+ * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
+ * @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, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
+
+    i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+    i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM
+    i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM
+    i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+    i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt)
+    i += put_uint16_t_by_index(battery_remaining, i, msg->payload); // Remaining battery energy: (0%: 0, 100%: 1000)
+    i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV)
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+ * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
+ * @param status System status flag, see MAV_STATUS ENUM
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
+ * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
+ * @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, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
+
+    i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+    i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM
+    i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM
+    i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+    i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt)
+    i += put_uint16_t_by_index(battery_remaining, i, msg->payload); // Remaining battery energy: (0%: 0, 100%: 1000)
+    i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV)
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a sys_status struct into a 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 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->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->battery_remaining, sys_status->packet_drop);
+}
+
+/**
+ * @brief Send a sys_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+ * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
+ * @param status System status flag, see MAV_STATUS ENUM
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
+ * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
+ * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
+{
+    mavlink_message_t msg;
+    mavlink_msg_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SYS_STATUS UNPACKING
+
+/**
+ * @brief Get field mode from sys_status message
+ *
+ * @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+ */
+static inline uint8_t mavlink_msg_sys_status_get_mode(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field nav_mode from sys_status message
+ *
+ * @return Navigation mode, see MAV_NAV_MODE ENUM
+ */
+static inline uint8_t mavlink_msg_sys_status_get_nav_mode(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field status from sys_status message
+ *
+ * @return System status flag, see MAV_STATUS ENUM
+ */
+static inline uint8_t mavlink_msg_sys_status_get_status(const mavlink_message_t* msg)
+{
+    return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @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)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+    return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field vbat from sys_status message
+ *
+ * @return Battery voltage, in millivolts (1 = 1 millivolt)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_vbat(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+    return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field battery_remaining from sys_status message
+ *
+ * @return Remaining battery energy: (0%: 0, 100%: 1000)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+    return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field packet_drop from sys_status message
+ *
+ * @return Dropped packets (packets that were corrupted on reception on the MAV)
+ */
+static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+    r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+    return (uint16_t)r.s;
+}
+
+/**
+ * @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)
+{
+    sys_status->mode = mavlink_msg_sys_status_get_mode(msg);
+    sys_status->nav_mode = mavlink_msg_sys_status_get_nav_mode(msg);
+    sys_status->status = mavlink_msg_sys_status_get_status(msg);
+    sys_status->load = mavlink_msg_sys_status_get_load(msg);
+    sys_status->vbat = mavlink_msg_sys_status_get_vbat(msg);
+    sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
+    sys_status->packet_drop = mavlink_msg_sys_status_get_packet_drop(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_system_time.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,110 @@
+// MESSAGE SYSTEM_TIME PACKING
+
+#define MAVLINK_MSG_ID_SYSTEM_TIME 2
+
+typedef struct __mavlink_system_time_t 
+{
+	uint64_t time_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch.
+
+} mavlink_system_time_t;
+
+
+
+/**
+ * @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_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ * @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_usec)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
+
+	i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch.
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ * @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_usec)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
+
+	i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch.
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a system_time struct into a 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 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_usec);
+}
+
+/**
+ * @brief Send a system_time message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec)
+{
+	mavlink_message_t msg;
+	mavlink_msg_system_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_usec);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SYSTEM_TIME UNPACKING
+
+/**
+ * @brief Get field time_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_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @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)
+{
+	system_time->time_usec = mavlink_msg_system_time_get_time_usec(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_system_time_utc.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,128 @@
+// MESSAGE SYSTEM_TIME_UTC PACKING
+
+#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC 4
+
+typedef struct __mavlink_system_time_utc_t 
+{
+	uint32_t utc_date; ///< GPS UTC date ddmmyy
+	uint32_t utc_time; ///< GPS UTC time hhmmss
+
+} mavlink_system_time_utc_t;
+
+
+
+/**
+ * @brief Pack a system_time_utc 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 utc_date GPS UTC date ddmmyy
+ * @param utc_time GPS UTC time hhmmss
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t utc_date, uint32_t utc_time)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC;
+
+	i += put_uint32_t_by_index(utc_date, i, msg->payload); // GPS UTC date ddmmyy
+	i += put_uint32_t_by_index(utc_time, i, msg->payload); // GPS UTC time hhmmss
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a system_time_utc message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param utc_date GPS UTC date ddmmyy
+ * @param utc_time GPS UTC time hhmmss
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t utc_date, uint32_t utc_time)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC;
+
+	i += put_uint32_t_by_index(utc_date, i, msg->payload); // GPS UTC date ddmmyy
+	i += put_uint32_t_by_index(utc_time, i, msg->payload); // GPS UTC time hhmmss
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a system_time_utc struct into a 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 system_time_utc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_system_time_utc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_utc_t* system_time_utc)
+{
+	return mavlink_msg_system_time_utc_pack(system_id, component_id, msg, system_time_utc->utc_date, system_time_utc->utc_time);
+}
+
+/**
+ * @brief Send a system_time_utc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param utc_date GPS UTC date ddmmyy
+ * @param utc_time GPS UTC time hhmmss
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_system_time_utc_send(mavlink_channel_t chan, uint32_t utc_date, uint32_t utc_time)
+{
+	mavlink_message_t msg;
+	mavlink_msg_system_time_utc_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, utc_date, utc_time);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SYSTEM_TIME_UTC UNPACKING
+
+/**
+ * @brief Get field utc_date from system_time_utc message
+ *
+ * @return GPS UTC date ddmmyy
+ */
+static inline uint32_t mavlink_msg_system_time_utc_get_utc_date(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field utc_time from system_time_utc message
+ *
+ * @return GPS UTC time hhmmss
+ */
+static inline uint32_t mavlink_msg_system_time_utc_get_utc_time(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint32_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Decode a system_time_utc message into a struct
+ *
+ * @param msg The message to decode
+ * @param system_time_utc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_system_time_utc_decode(const mavlink_message_t* msg, mavlink_system_time_utc_t* system_time_utc)
+{
+	system_time_utc->utc_date = mavlink_msg_system_time_utc_get_utc_date(msg);
+	system_time_utc->utc_time = mavlink_msg_system_time_utc_get_utc_time(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_vfr_hud.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,212 @@
+// MESSAGE VFR_HUD PACKING
+
+#define MAVLINK_MSG_ID_VFR_HUD 74
+
+typedef struct __mavlink_vfr_hud_t 
+{
+    float airspeed; ///< Current airspeed in m/s
+    float groundspeed; ///< Current ground speed in m/s
+    int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north)
+    uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100
+    float alt; ///< Current altitude (MSL), in meters
+    float climb; ///< Current climb rate in meters/second
+
+} mavlink_vfr_hud_t;
+
+
+
+/**
+ * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s
+ * @param groundspeed Current ground speed in m/s
+ * @param heading Current heading in degrees, in compass units (0..360, 0=north)
+ * @param throttle Current throttle setting in integer percent, 0 to 100
+ * @param alt Current altitude (MSL), in meters
+ * @param climb Current climb rate in meters/second
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
+
+    i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s
+    i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s
+    i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north)
+    i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100
+    i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
+    i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a vfr_hud message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param airspeed Current airspeed in m/s
+ * @param groundspeed Current ground speed in m/s
+ * @param heading Current heading in degrees, in compass units (0..360, 0=north)
+ * @param throttle Current throttle setting in integer percent, 0 to 100
+ * @param alt Current altitude (MSL), in meters
+ * @param climb Current climb rate in meters/second
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
+
+    i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s
+    i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s
+    i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north)
+    i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100
+    i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
+    i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a vfr_hud struct into a 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 vfr_hud C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud)
+{
+    return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
+}
+
+/**
+ * @brief Send a vfr_hud message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param airspeed Current airspeed in m/s
+ * @param groundspeed Current ground speed in m/s
+ * @param heading Current heading in degrees, in compass units (0..360, 0=north)
+ * @param throttle Current throttle setting in integer percent, 0 to 100
+ * @param alt Current altitude (MSL), in meters
+ * @param climb Current climb rate in meters/second
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
+{
+    mavlink_message_t msg;
+    mavlink_msg_vfr_hud_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed, groundspeed, heading, throttle, alt, climb);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE VFR_HUD UNPACKING
+
+/**
+ * @brief Get field airspeed from vfr_hud message
+ *
+ * @return Current airspeed in m/s
+ */
+static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload)[0];
+    r.b[2] = (msg->payload)[1];
+    r.b[1] = (msg->payload)[2];
+    r.b[0] = (msg->payload)[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field groundspeed from vfr_hud message
+ *
+ * @return Current ground speed in m/s
+ */
+static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field heading from vfr_hud message
+ *
+ * @return Current heading in degrees, in compass units (0..360, 0=north)
+ */
+static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0];
+    r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1];
+    return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field throttle from vfr_hud message
+ *
+ * @return Current throttle setting in integer percent, 0 to 100
+ */
+static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
+{
+    generic_16bit r;
+    r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
+    r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[1];
+    return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field alt from vfr_hud message
+ *
+ * @return Current altitude (MSL), in meters
+ */
+static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[0];
+    r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[1];
+    r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[2];
+    r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field climb from vfr_hud message
+ *
+ * @return Current climb rate in meters/second
+ */
+static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a vfr_hud message into a struct
+ *
+ * @param msg The message to decode
+ * @param vfr_hud C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
+{
+    vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
+    vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
+    vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
+    vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
+    vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
+    vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,360 @@
+// MESSAGE WAYPOINT PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT 39
+
+typedef struct __mavlink_waypoint_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t seq; ///< Sequence
+	uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+	uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+	uint8_t current; ///< false:0, true:1
+	uint8_t autocontinue; ///< autocontinue to next wp
+	float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+	float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+	float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+	float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+	float x; ///< PARAM5 / local: x position, global: latitude
+	float y; ///< PARAM6 / y position: global: longitude
+	float z; ///< PARAM7 / z position: global: altitude
+
+} mavlink_waypoint_t;
+
+
+
+/**
+ * @brief Pack a waypoint 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 target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+ * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+ * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
+ * @param z PARAM7 / z position: global: altitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+	i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+	i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+	i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
+	i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
+	i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+	i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+	i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+	i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+	i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
+	i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
+	i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+ * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+ * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
+ * @param z PARAM7 / z position: global: altitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+	i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+	i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+	i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
+	i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
+	i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+	i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+	i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+	i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+	i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
+	i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
+	i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint struct into a 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 waypoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
+{
+	return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z);
+}
+
+/**
+ * @brief Send a waypoint message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+ * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+ * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
+ * @param z PARAM7 / z position: global: altitude
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field seq from waypoint message
+ *
+ * @return Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field frame from waypoint message
+ *
+ * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+ */
+static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Get field command from waypoint message
+ *
+ * @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+ */
+static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field current from waypoint message
+ *
+ * @return false:0, true:1
+ */
+static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field autocontinue from waypoint message
+ *
+ * @return autocontinue to next wp
+ */
+static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field param1 from waypoint message
+ *
+ * @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+ */
+static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param2 from waypoint message
+ *
+ * @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ */
+static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param3 from waypoint message
+ *
+ * @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+ */
+static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field param4 from waypoint message
+ *
+ * @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+ */
+static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field x from waypoint message
+ *
+ * @return PARAM5 / local: x position, global: latitude
+ */
+static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from waypoint message
+ *
+ * @return PARAM6 / y position: global: longitude
+ */
+static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from waypoint message
+ *
+ * @return PARAM7 / z position: global: altitude
+ */
+static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a waypoint message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint)
+{
+	waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg);
+	waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg);
+	waypoint->seq = mavlink_msg_waypoint_get_seq(msg);
+	waypoint->frame = mavlink_msg_waypoint_get_frame(msg);
+	waypoint->command = mavlink_msg_waypoint_get_command(msg);
+	waypoint->current = mavlink_msg_waypoint_get_current(msg);
+	waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg);
+	waypoint->param1 = mavlink_msg_waypoint_get_param1(msg);
+	waypoint->param2 = mavlink_msg_waypoint_get_param2(msg);
+	waypoint->param3 = mavlink_msg_waypoint_get_param3(msg);
+	waypoint->param4 = mavlink_msg_waypoint_get_param4(msg);
+	waypoint->x = mavlink_msg_waypoint_get_x(msg);
+	waypoint->y = mavlink_msg_waypoint_get_y(msg);
+	waypoint->z = mavlink_msg_waypoint_get_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_ack.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,135 @@
+// MESSAGE WAYPOINT_ACK PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_ACK 47
+
+typedef struct __mavlink_waypoint_ack_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint8_t type; ///< 0: OK, 1: Error
+
+} mavlink_waypoint_ack_t;
+
+
+
+/**
+ * @brief Pack a waypoint_ack 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 target_system System ID
+ * @param target_component Component ID
+ * @param type 0: OK, 1: Error
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t type)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_ack message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param type 0: OK, 1: Error
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t type)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_ack struct into a 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 waypoint_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack)
+{
+	return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type);
+}
+
+/**
+ * @brief Send a waypoint_ack message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param type 0: OK, 1: Error
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, type);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_ACK UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_ack message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_ack_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_ack message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_ack_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field type from waypoint_ack message
+ *
+ * @return 0: OK, 1: Error
+ */
+static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a waypoint_ack message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_ack C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack)
+{
+	waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg);
+	waypoint_ack->target_component = mavlink_msg_waypoint_ack_get_target_component(msg);
+	waypoint_ack->type = mavlink_msg_waypoint_ack_get_type(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_clear_all.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE WAYPOINT_CLEAR_ALL PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45
+
+typedef struct __mavlink_waypoint_clear_all_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+
+} mavlink_waypoint_clear_all_t;
+
+
+
+/**
+ * @brief Pack a waypoint_clear_all 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 target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_clear_all message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_clear_all struct into a 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 waypoint_clear_all C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all)
+{
+	return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component);
+}
+
+/**
+ * @brief Send a waypoint_clear_all message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_clear_all_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_clear_all message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_clear_all message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a waypoint_clear_all message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_clear_all C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all)
+{
+	waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg);
+	waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_count.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,138 @@
+// MESSAGE WAYPOINT_COUNT PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44
+
+typedef struct __mavlink_waypoint_count_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t count; ///< Number of Waypoints in the Sequence
+
+} mavlink_waypoint_count_t;
+
+
+
+/**
+ * @brief Pack a waypoint_count 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 target_system System ID
+ * @param target_component Component ID
+ * @param count Number of Waypoints in the Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_count message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param count Number of Waypoints in the Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_count struct into a 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 waypoint_count C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count)
+{
+	return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count);
+}
+
+/**
+ * @brief Send a waypoint_count message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param count Number of Waypoints in the Sequence
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_count_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, count);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_COUNT UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_count message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_count message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field count from waypoint_count message
+ *
+ * @return Number of Waypoints in the Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a waypoint_count message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_count C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count)
+{
+	waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg);
+	waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg);
+	waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_current.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,104 @@
+// MESSAGE WAYPOINT_CURRENT PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42
+
+typedef struct __mavlink_waypoint_current_t 
+{
+	uint16_t seq; ///< Sequence
+
+} mavlink_waypoint_current_t;
+
+
+
+/**
+ * @brief Pack a waypoint_current 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 seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
+
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_current message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
+
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_current struct into a 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 waypoint_current C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
+{
+	return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
+}
+
+/**
+ * @brief Send a waypoint_current message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param seq Sequence
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_CURRENT UNPACKING
+
+/**
+ * @brief Get field seq from waypoint_current message
+ *
+ * @return Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a waypoint_current message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_current C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current)
+{
+	waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_reached.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,104 @@
+// MESSAGE WAYPOINT_REACHED PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_REACHED 46
+
+typedef struct __mavlink_waypoint_reached_t 
+{
+	uint16_t seq; ///< Sequence
+
+} mavlink_waypoint_reached_t;
+
+
+
+/**
+ * @brief Pack a waypoint_reached 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 seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
+
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_reached message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
+
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_reached struct into a 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 waypoint_reached C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached)
+{
+	return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq);
+}
+
+/**
+ * @brief Send a waypoint_reached message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param seq Sequence
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_reached_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_REACHED UNPACKING
+
+/**
+ * @brief Get field seq from waypoint_reached message
+ *
+ * @return Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_reached_get_seq(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a waypoint_reached message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_reached C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached)
+{
+	waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_request.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,138 @@
+// MESSAGE WAYPOINT_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40
+
+typedef struct __mavlink_waypoint_request_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t seq; ///< Sequence
+
+} mavlink_waypoint_request_t;
+
+
+
+/**
+ * @brief Pack a waypoint_request 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 target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_request message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_request struct into a 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 waypoint_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request)
+{
+	return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq);
+}
+
+/**
+ * @brief Send a waypoint_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_request_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_REQUEST UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_request message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_request message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field seq from waypoint_request message
+ *
+ * @return Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a waypoint_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request)
+{
+	waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg);
+	waypoint_request->target_component = mavlink_msg_waypoint_request_get_target_component(msg);
+	waypoint_request->seq = mavlink_msg_waypoint_request_get_seq(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_request_list.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,118 @@
+// MESSAGE WAYPOINT_REQUEST_LIST PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST 43
+
+typedef struct __mavlink_waypoint_request_list_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+
+} mavlink_waypoint_request_list_t;
+
+
+
+/**
+ * @brief Pack a waypoint_request_list 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 target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_request_list message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_request_list struct into a 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 waypoint_request_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list)
+{
+	return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component);
+}
+
+/**
+ * @brief Send a waypoint_request_list message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_REQUEST_LIST UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_request_list message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_request_list_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_request_list message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a waypoint_request_list message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_request_list C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list)
+{
+	waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg);
+	waypoint_request_list->target_component = mavlink_msg_waypoint_request_list_get_target_component(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/common/mavlink_msg_waypoint_set_current.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,138 @@
+// MESSAGE WAYPOINT_SET_CURRENT PACKING
+
+#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT 41
+
+typedef struct __mavlink_waypoint_set_current_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t seq; ///< Sequence
+
+} mavlink_waypoint_set_current_t;
+
+
+
+/**
+ * @brief Pack a waypoint_set_current 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 target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a waypoint_set_current message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_waypoint_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a waypoint_set_current struct into a 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 waypoint_set_current C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current)
+{
+	return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq);
+}
+
+/**
+ * @brief Send a waypoint_set_current message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Sequence
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+	mavlink_message_t msg;
+	mavlink_msg_waypoint_set_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WAYPOINT_SET_CURRENT UNPACKING
+
+/**
+ * @brief Get field target_system from waypoint_set_current message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_waypoint_set_current_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from waypoint_set_current message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_waypoint_set_current_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field seq from waypoint_set_current message
+ *
+ * @return Sequence
+ */
+static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a waypoint_set_current message into a struct
+ *
+ * @param msg The message to decode
+ * @param waypoint_set_current C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current)
+{
+	waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg);
+	waypoint_set_current->target_component = mavlink_msg_waypoint_set_current_get_target_component(msg);
+	waypoint_set_current->seq = mavlink_msg_waypoint_set_current_get_seq(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/mavlink_bridge.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,41 @@
+/* MAVLink adapter header */
+#ifndef __MAVLINK_BRIDGE_HEADER_H
+#define __MAVLINK_BRIDGE_HEADER_H
+ 
+#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+#include "mavlink_types.h"
+ 
+/* Struct that stores the communication settings of this system.
+   you can also define / alter these settings elsewhere, as long
+   as they're included BEFORE mavlink.h.
+   So you can set the
+ 
+   mavlink_system.sysid = 100; // System ID, 1-255
+   mavlink_system.compid = 50; // Component/Subsystem ID, 1-255
+ 
+   Lines also in your main.c, e.g. by reading these parameter from EEPROM.
+ */
+mavlink_system_t mavlink_system;
+ 
+/**
+ * @brief Send one char (uint8_t) over a comm channel
+ *
+ * @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
+ * @param ch Character to send
+ */
+static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch) {
+    extern Serial pc;
+    
+    if (chan == MAVLINK_COMM_0) {
+        pc.putc(ch);
+    }
+    if (chan == MAVLINK_COMM_1) {
+        // write to mavlink logfile
+    }
+}
+ 
+#include "protocol.h"
+#include "common/common.h"
+ 
+#endif /* YOUR_MAVLINK_BRIDGE_HEADER_H *//* MAVLink adapter header */
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/mavlink_types.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,252 @@
+#ifndef MAVLINK_TYPES_H_
+#define MAVLINK_TYPES_H_
+
+#include "inttypes.h"
+
+enum MAV_CLASS
+{
+    MAV_CLASS_GENERIC = 0,        ///< Generic autopilot, full support for everything
+    MAV_CLASS_PIXHAWK = 1,        ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
+    MAV_CLASS_SLUGS = 2,          ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
+    MAV_CLASS_ARDUPILOTMEGA = 3,  ///< ArduPilotMega / ArduCopter, http://diydrones.com
+    MAV_CLASS_OPENPILOT = 4,      ///< OpenPilot, http://openpilot.org
+    MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5,  ///< Generic autopilot only supporting simple waypoints
+    MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
+    MAV_CLASS_GENERIC_MISSION_FULL = 7,            ///< Generic autopilot supporting the full mission command set
+    MAV_CLASS_NONE = 8,           ///< No valid autopilot
+    MAV_CLASS_NB                  ///< Number of autopilot classes
+};
+
+enum MAV_ACTION
+{
+    MAV_ACTION_HOLD = 0,
+    MAV_ACTION_MOTORS_START = 1,
+    MAV_ACTION_LAUNCH = 2,
+    MAV_ACTION_RETURN = 3,
+    MAV_ACTION_EMCY_LAND = 4,
+    MAV_ACTION_EMCY_KILL = 5,
+    MAV_ACTION_CONFIRM_KILL = 6,
+    MAV_ACTION_CONTINUE = 7,
+    MAV_ACTION_MOTORS_STOP = 8,
+    MAV_ACTION_HALT = 9,
+    MAV_ACTION_SHUTDOWN = 10,
+    MAV_ACTION_REBOOT = 11,
+    MAV_ACTION_SET_MANUAL = 12,
+    MAV_ACTION_SET_AUTO = 13,
+    MAV_ACTION_STORAGE_READ = 14,
+    MAV_ACTION_STORAGE_WRITE = 15,
+    MAV_ACTION_CALIBRATE_RC = 16,
+    MAV_ACTION_CALIBRATE_GYRO = 17,
+    MAV_ACTION_CALIBRATE_MAG = 18,
+    MAV_ACTION_CALIBRATE_ACC = 19,
+    MAV_ACTION_CALIBRATE_PRESSURE = 20,
+    MAV_ACTION_REC_START = 21,
+    MAV_ACTION_REC_PAUSE = 22,
+    MAV_ACTION_REC_STOP = 23,
+    MAV_ACTION_TAKEOFF = 24,
+    MAV_ACTION_NAVIGATE = 25,
+    MAV_ACTION_LAND = 26,
+    MAV_ACTION_LOITER = 27,
+    MAV_ACTION_SET_ORIGIN = 28,
+    MAV_ACTION_RELAY_ON = 29,
+    MAV_ACTION_RELAY_OFF = 30,
+    MAV_ACTION_GET_IMAGE = 31,
+    MAV_ACTION_VIDEO_START = 32,
+    MAV_ACTION_VIDEO_STOP = 33,
+    MAV_ACTION_RESET_MAP = 34,
+    MAV_ACTION_RESET_PLAN = 35,
+    MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
+    MAV_ACTION_ASCEND_AT_RATE = 37,
+    MAV_ACTION_CHANGE_MODE = 38,
+    MAV_ACTION_LOITER_MAX_TURNS = 39,
+    MAV_ACTION_LOITER_MAX_TIME = 40,
+        MAV_ACTION_START_HILSIM = 41,
+        MAV_ACTION_STOP_HILSIM = 42,    
+    MAV_ACTION_NB        ///< Number of MAV actions
+};
+
+enum MAV_MODE
+{
+    MAV_MODE_UNINIT = 0,     ///< System is in undefined state
+    MAV_MODE_LOCKED = 1,     ///< Motors are blocked, system is safe
+    MAV_MODE_MANUAL = 2,     ///< System is allowed to be active, under manual (RC) control
+    MAV_MODE_GUIDED = 3,     ///< System is allowed to be active, under autonomous control, manual setpoint
+    MAV_MODE_AUTO =   4,     ///< System is allowed to be active, under autonomous control and navigation
+    MAV_MODE_TEST1 =  5,     ///< Generic test mode, for custom use
+    MAV_MODE_TEST2 =  6,     ///< Generic test mode, for custom use
+    MAV_MODE_TEST3 =  7,     ///< Generic test mode, for custom use
+    MAV_MODE_READY =  8,     ///< System is ready, motors are unblocked, but controllers are inactive
+    MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
+};
+
+enum MAV_STATE
+{
+    MAV_STATE_UNINIT = 0,
+    MAV_STATE_BOOT,
+    MAV_STATE_CALIBRATING,
+    MAV_STATE_STANDBY,
+    MAV_STATE_ACTIVE,
+    MAV_STATE_CRITICAL,
+    MAV_STATE_EMERGENCY,
+    MAV_STATE_HILSIM,
+    MAV_STATE_POWEROFF
+};
+
+enum MAV_NAV
+{
+    MAV_NAV_GROUNDED = 0,
+    MAV_NAV_LIFTOFF,
+    MAV_NAV_HOLD,
+    MAV_NAV_WAYPOINT,
+    MAV_NAV_VECTOR,
+    MAV_NAV_RETURNING,
+    MAV_NAV_LANDING,
+    MAV_NAV_LOST,
+    MAV_NAV_LOITER,
+    MAV_NAV_FREE_DRIFT
+};
+
+enum MAV_TYPE
+{
+    MAV_GENERIC = 0,
+    MAV_FIXED_WING = 1,
+    MAV_QUADROTOR = 2,
+    MAV_COAXIAL = 3,
+    MAV_HELICOPTER = 4,
+    MAV_GROUND = 5,
+    OCU = 6,
+    MAV_AIRSHIP = 7,
+    MAV_FREE_BALLOON = 8,
+    MAV_ROCKET = 9,
+    UGV_GROUND_ROVER = 10,
+    UGV_SURFACE_SHIP = 11
+};
+
+enum MAV_AUTOPILOT_TYPE
+{
+    MAV_AUTOPILOT_GENERIC = 0,
+    MAV_AUTOPILOT_PIXHAWK = 1,
+    MAV_AUTOPILOT_SLUGS = 2,
+    MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
+    MAV_AUTOPILOT_NONE = 4
+};
+
+enum MAV_COMPONENT
+{
+    MAV_COMP_ID_GPS,
+    MAV_COMP_ID_WAYPOINTPLANNER,
+    MAV_COMP_ID_BLOBTRACKER,
+    MAV_COMP_ID_PATHPLANNER,
+    MAV_COMP_ID_AIRSLAM,
+    MAV_COMP_ID_MAPPER,
+    MAV_COMP_ID_CAMERA,
+    MAV_COMP_ID_IMU = 200,
+    MAV_COMP_ID_IMU_2 = 201,
+    MAV_COMP_ID_IMU_3 = 202,
+    MAV_COMP_ID_UDP_BRIDGE = 240,
+    MAV_COMP_ID_UART_BRIDGE = 241,
+    MAV_COMP_ID_SYSTEM_CONTROL = 250
+};
+
+enum MAV_FRAME
+{
+    MAV_FRAME_GLOBAL = 0,
+    MAV_FRAME_LOCAL = 1,
+    MAV_FRAME_MISSION = 2,
+    MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
+        MAV_FRAME_LOCAL_ENU = 4
+};
+
+enum MAVLINK_DATA_STREAM_TYPE
+{
+    MAVLINK_DATA_STREAM_IMG_JPEG,
+    MAVLINK_DATA_STREAM_IMG_BMP,
+    MAVLINK_DATA_STREAM_IMG_RAW8U,
+    MAVLINK_DATA_STREAM_IMG_RAW32U,
+    MAVLINK_DATA_STREAM_IMG_PGM,
+    MAVLINK_DATA_STREAM_IMG_PNG
+    
+};
+
+//#define MAVLINK_STX 0x55 ///< Packet start sign
+#define MAVLINK_STX 0xFE ///< Packet start sign
+#define MAVLINK_STX_LEN 1 ///< Length of start sign
+#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
+
+#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 + MAVLINK_STX_LEN) ///< 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_NUM_NON_STX_PAYLOAD_BYTES (MAVLINK_NUM_NON_PAYLOAD_BYTES - MAVLINK_STX_LEN)
+
+#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
+//#define MAVLINK_MAX_DATA_LEN MAVLINK_MAX_PACKET_LEN - MAVLINK_STX_LEN
+
+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
+    uint8_t type;    ///< Unused, can be used by user to store the system's type
+    uint8_t state;   ///< Unused, can be used by user to store the system's state
+    uint8_t mode;    ///< Unused, can be used by user to store the system's mode
+    uint8_t nav_mode;    ///< Unused, can be used by user to store the system's navigation mode
+} mavlink_system_t;
+
+typedef struct __mavlink_message {
+    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
+    uint8_t payload[MAVLINK_MAX_PAYLOAD_LEN]; ///< Payload data, ALIGNMENT IMPORTANT ON MCU
+    uint8_t ck_a;    ///< Checksum high byte
+    uint8_t ck_b;    ///< Checksum low byte
+} mavlink_message_t;
+
+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_t; ///< The state machine for the comm parser
+
+typedef struct __mavlink_status {
+    uint8_t ck_a;                       ///< Checksum byte 1
+    uint8_t ck_b;                       ///< Checksum byte 2
+    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;
+
+#endif /* MAVLINK_TYPES_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/minimal/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "minimal.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/minimal/mavlink_msg_heartbeat.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,132 @@
+// MESSAGE HEARTBEAT PACKING
+
+#define MAVLINK_MSG_ID_HEARTBEAT 0
+
+typedef struct __mavlink_heartbeat_t 
+{
+	uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+	uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+	uint8_t mavlink_version; ///< MAVLink version
+
+} mavlink_heartbeat_t;
+
+
+
+/**
+ * @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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE 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)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+	i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+	i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @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 chan The MAVLink channel this message was 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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE 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)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+	i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+	i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a heartbeat struct into a 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 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);
+}
+
+/**
+ * @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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
+{
+	mavlink_message_t msg;
+	mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot);
+	mavlink_send_uart(chan, &msg);
+}
+
+#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 (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field autopilot from heartbeat message
+ *
+ * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+ */
+static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @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 (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @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)
+{
+	heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
+	heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
+	heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/minimal/minimal.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,45 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://qgroundcontrol.org/mavlink/
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef MINIMAL_H
+#define MINIMAL_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_MINIMAL
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+// ENUM DEFINITIONS
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_heartbeat.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {  }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Sunday, September 11 2011, 13:52 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "pixhawk.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_attitude_control.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,257 @@
+// MESSAGE ATTITUDE_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE_CONTROL 85
+
+typedef struct __mavlink_attitude_control_t 
+{
+	uint8_t target; ///< The system to be controlled
+	float roll; ///< roll
+	float pitch; ///< pitch
+	float yaw; ///< yaw
+	float thrust; ///< thrust
+	uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
+	uint8_t pitch_manual; ///< pitch auto:0, manual:1
+	uint8_t yaw_manual; ///< yaw auto:0, manual:1
+	uint8_t thrust_manual; ///< thrust auto:0, manual:1
+
+} mavlink_attitude_control_t;
+
+
+
+/**
+ * @brief Pack a attitude_control 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 target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
+	i += put_float_by_index(roll, i, msg->payload); // roll
+	i += put_float_by_index(pitch, i, msg->payload); // pitch
+	i += put_float_by_index(yaw, i, msg->payload); // yaw
+	i += put_float_by_index(thrust, i, msg->payload); // thrust
+	i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
+	i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
+	i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
+	i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a attitude_control message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
+	i += put_float_by_index(roll, i, msg->payload); // roll
+	i += put_float_by_index(pitch, i, msg->payload); // pitch
+	i += put_float_by_index(yaw, i, msg->payload); // yaw
+	i += put_float_by_index(thrust, i, msg->payload); // thrust
+	i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
+	i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
+	i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
+	i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a attitude_control struct into a 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 attitude_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control)
+{
+	return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
+}
+
+/**
+ * @brief Send a attitude_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system to be controlled
+ * @param roll roll
+ * @param pitch pitch
+ * @param yaw yaw
+ * @param thrust thrust
+ * @param roll_manual roll control enabled auto:0, manual:1
+ * @param pitch_manual pitch auto:0, manual:1
+ * @param yaw_manual yaw auto:0, manual:1
+ * @param thrust_manual thrust auto:0, manual:1
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
+{
+	mavlink_message_t msg;
+	mavlink_msg_attitude_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ATTITUDE_CONTROL UNPACKING
+
+/**
+ * @brief Get field target from attitude_control message
+ *
+ * @return The system to be controlled
+ */
+static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field roll from attitude_control message
+ *
+ * @return roll
+ */
+static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from attitude_control message
+ *
+ * @return pitch
+ */
+static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from attitude_control message
+ *
+ * @return yaw
+ */
+static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field thrust from attitude_control message
+ *
+ * @return thrust
+ */
+static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll_manual from attitude_control message
+ *
+ * @return roll control enabled auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_attitude_control_get_roll_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+}
+
+/**
+ * @brief Get field pitch_manual from attitude_control message
+ *
+ * @return pitch auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_attitude_control_get_pitch_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field yaw_manual from attitude_control message
+ *
+ * @return yaw auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_attitude_control_get_yaw_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field thrust_manual from attitude_control message
+ *
+ * @return thrust auto:0, manual:1
+ */
+static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a attitude_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param attitude_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control)
+{
+	attitude_control->target = mavlink_msg_attitude_control_get_target(msg);
+	attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg);
+	attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg);
+	attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg);
+	attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg);
+	attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg);
+	attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg);
+	attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg);
+	attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_aux_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,204 @@
+// MESSAGE AUX_STATUS PACKING
+
+#define MAVLINK_MSG_ID_AUX_STATUS 142
+
+typedef struct __mavlink_aux_status_t 
+{
+	uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+	uint16_t i2c0_err_count; ///< Number of I2C errors since startup
+	uint16_t i2c1_err_count; ///< Number of I2C errors since startup
+	uint16_t spi0_err_count; ///< Number of I2C errors since startup
+	uint16_t spi1_err_count; ///< Number of I2C errors since startup
+	uint16_t uart_total_err_count; ///< Number of I2C errors since startup
+
+} mavlink_aux_status_t;
+
+
+
+/**
+ * @brief Pack a aux_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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param i2c0_err_count Number of I2C errors since startup
+ * @param i2c1_err_count Number of I2C errors since startup
+ * @param spi0_err_count Number of I2C errors since startup
+ * @param spi1_err_count Number of I2C errors since startup
+ * @param uart_total_err_count Number of I2C errors since startup
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aux_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
+
+	i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+	i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a aux_status message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param i2c0_err_count Number of I2C errors since startup
+ * @param i2c1_err_count Number of I2C errors since startup
+ * @param spi0_err_count Number of I2C errors since startup
+ * @param spi1_err_count Number of I2C errors since startup
+ * @param uart_total_err_count Number of I2C errors since startup
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aux_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
+
+	i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+	i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
+	i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a aux_status struct into a 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 aux_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status)
+{
+	return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count);
+}
+
+/**
+ * @brief Send a aux_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ * @param i2c0_err_count Number of I2C errors since startup
+ * @param i2c1_err_count Number of I2C errors since startup
+ * @param spi0_err_count Number of I2C errors since startup
+ * @param spi1_err_count Number of I2C errors since startup
+ * @param uart_total_err_count Number of I2C errors since startup
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
+{
+	mavlink_message_t msg;
+	mavlink_msg_aux_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE AUX_STATUS UNPACKING
+
+/**
+ * @brief Get field load from aux_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_aux_status_get_load(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field i2c0_err_count from aux_status message
+ *
+ * @return Number of I2C errors since startup
+ */
+static inline uint16_t mavlink_msg_aux_status_get_i2c0_err_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field i2c1_err_count from aux_status message
+ *
+ * @return Number of I2C errors since startup
+ */
+static inline uint16_t mavlink_msg_aux_status_get_i2c1_err_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field spi0_err_count from aux_status message
+ *
+ * @return Number of I2C errors since startup
+ */
+static inline uint16_t mavlink_msg_aux_status_get_spi0_err_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field spi1_err_count from aux_status message
+ *
+ * @return Number of I2C errors since startup
+ */
+static inline uint16_t mavlink_msg_aux_status_get_spi1_err_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field uart_total_err_count from aux_status message
+ *
+ * @return Number of I2C errors since startup
+ */
+static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a aux_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param aux_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status)
+{
+	aux_status->load = mavlink_msg_aux_status_get_load(msg);
+	aux_status->i2c0_err_count = mavlink_msg_aux_status_get_i2c0_err_count(msg);
+	aux_status->i2c1_err_count = mavlink_msg_aux_status_get_i2c1_err_count(msg);
+	aux_status->spi0_err_count = mavlink_msg_aux_status_get_spi0_err_count(msg);
+	aux_status->spi1_err_count = mavlink_msg_aux_status_get_spi1_err_count(msg);
+	aux_status->uart_total_err_count = mavlink_msg_aux_status_get_uart_total_err_count(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_brief_feature.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,249 @@
+// MESSAGE BRIEF_FEATURE PACKING
+
+#define MAVLINK_MSG_ID_BRIEF_FEATURE 172
+
+typedef struct __mavlink_brief_feature_t 
+{
+	float x; ///< x position in m
+	float y; ///< y position in m
+	float z; ///< z position in m
+	uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true
+	uint16_t size; ///< Size in pixels
+	uint16_t orientation; ///< Orientation
+	uint8_t descriptor[32]; ///< Descriptor
+	float response; ///< Harris operator response at this location
+
+} mavlink_brief_feature_t;
+
+#define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32
+
+
+/**
+ * @brief Pack a brief_feature 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 x x position in m
+ * @param y y position in m
+ * @param z z position in m
+ * @param orientation_assignment Orientation assignment 0: false, 1:true
+ * @param size Size in pixels
+ * @param orientation Orientation
+ * @param descriptor Descriptor
+ * @param response Harris operator response at this location
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
+
+	i += put_float_by_index(x, i, msg->payload); // x position in m
+	i += put_float_by_index(y, i, msg->payload); // y position in m
+	i += put_float_by_index(z, i, msg->payload); // z position in m
+	i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true
+	i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels
+	i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation
+	i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor
+	i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a brief_feature message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param x x position in m
+ * @param y y position in m
+ * @param z z position in m
+ * @param orientation_assignment Orientation assignment 0: false, 1:true
+ * @param size Size in pixels
+ * @param orientation Orientation
+ * @param descriptor Descriptor
+ * @param response Harris operator response at this location
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
+
+	i += put_float_by_index(x, i, msg->payload); // x position in m
+	i += put_float_by_index(y, i, msg->payload); // y position in m
+	i += put_float_by_index(z, i, msg->payload); // z position in m
+	i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true
+	i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels
+	i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation
+	i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor
+	i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a brief_feature struct into a 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 brief_feature C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature)
+{
+	return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response);
+}
+
+/**
+ * @brief Send a brief_feature message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param x x position in m
+ * @param y y position in m
+ * @param z z position in m
+ * @param orientation_assignment Orientation assignment 0: false, 1:true
+ * @param size Size in pixels
+ * @param orientation Orientation
+ * @param descriptor Descriptor
+ * @param response Harris operator response at this location
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
+{
+	mavlink_message_t msg;
+	mavlink_msg_brief_feature_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, orientation_assignment, size, orientation, descriptor, response);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE BRIEF_FEATURE UNPACKING
+
+/**
+ * @brief Get field x from brief_feature message
+ *
+ * @return x position in m
+ */
+static inline float mavlink_msg_brief_feature_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from brief_feature message
+ *
+ * @return y position in m
+ */
+static inline float mavlink_msg_brief_feature_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from brief_feature message
+ *
+ * @return z position in m
+ */
+static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field orientation_assignment from brief_feature message
+ *
+ * @return Orientation assignment 0: false, 1:true
+ */
+static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+}
+
+/**
+ * @brief Get field size from brief_feature message
+ *
+ * @return Size in pixels
+ */
+static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field orientation from brief_feature message
+ *
+ * @return Orientation
+ */
+static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field descriptor from brief_feature message
+ *
+ * @return Descriptor
+ */
+static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t), sizeof(uint8_t)*32);
+	return sizeof(uint8_t)*32;
+}
+
+/**
+ * @brief Get field response from brief_feature message
+ *
+ * @return Harris operator response at this location
+ */
+static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a brief_feature message into a struct
+ *
+ * @param msg The message to decode
+ * @param brief_feature C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature)
+{
+	brief_feature->x = mavlink_msg_brief_feature_get_x(msg);
+	brief_feature->y = mavlink_msg_brief_feature_get_y(msg);
+	brief_feature->z = mavlink_msg_brief_feature_get_z(msg);
+	brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg);
+	brief_feature->size = mavlink_msg_brief_feature_get_size(msg);
+	brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg);
+	mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor);
+	brief_feature->response = mavlink_msg_brief_feature_get_response(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,174 @@
+// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
+
+#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 170
+
+typedef struct __mavlink_data_transmission_handshake_t 
+{
+	uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+	uint32_t size; ///< total data size in bytes (set on ACK only)
+	uint8_t packets; ///< number of packets beeing sent (set on ACK only)
+	uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+	uint8_t jpg_quality; ///< JPEG quality out of [1,100]
+
+} mavlink_data_transmission_handshake_t;
+
+
+
+/**
+ * @brief Pack a data_transmission_handshake 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 requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+ * @param size total data size in bytes (set on ACK only)
+ * @param packets number of packets beeing sent (set on ACK only)
+ * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+ * @param jpg_quality JPEG quality out of [1,100]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+	i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
+	i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
+	i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+	i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a data_transmission_handshake message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+ * @param size total data size in bytes (set on ACK only)
+ * @param packets number of packets beeing sent (set on ACK only)
+ * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+ * @param jpg_quality JPEG quality out of [1,100]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+	i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
+	i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
+	i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+	i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a data_transmission_handshake struct into a 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 data_transmission_handshake C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
+{
+	return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
+}
+
+/**
+ * @brief Send a data_transmission_handshake message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+ * @param size total data size in bytes (set on ACK only)
+ * @param packets number of packets beeing sent (set on ACK only)
+ * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+ * @param jpg_quality JPEG quality out of [1,100]
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
+{
+	mavlink_message_t msg;
+	mavlink_msg_data_transmission_handshake_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, size, packets, payload, jpg_quality);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
+
+/**
+ * @brief Get field type from data_transmission_handshake message
+ *
+ * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
+ */
+static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field size from data_transmission_handshake message
+ *
+ * @return total data size in bytes (set on ACK only)
+ */
+static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field packets from data_transmission_handshake message
+ *
+ * @return number of packets beeing sent (set on ACK only)
+ */
+static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t))[0];
+}
+
+/**
+ * @brief Get field payload from data_transmission_handshake message
+ *
+ * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
+ */
+static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field jpg_quality from data_transmission_handshake message
+ *
+ * @return JPEG quality out of [1,100]
+ */
+static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a data_transmission_handshake message into a struct
+ *
+ * @param msg The message to decode
+ * @param data_transmission_handshake C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
+{
+	data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
+	data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
+	data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
+	data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
+	data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_encapsulated_data.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,124 @@
+// MESSAGE ENCAPSULATED_DATA PACKING
+
+#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 171
+
+typedef struct __mavlink_encapsulated_data_t 
+{
+	uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
+	uint8_t data[253]; ///< image data bytes
+
+} mavlink_encapsulated_data_t;
+
+#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
+
+
+/**
+ * @brief Pack a encapsulated_data 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 seqnr sequence number (starting with 0 on every transmission)
+ * @param data image data bytes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
+
+	i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
+	i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a encapsulated_data message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param seqnr sequence number (starting with 0 on every transmission)
+ * @param data image data bytes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
+
+	i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
+	i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a encapsulated_data struct into a 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 encapsulated_data C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
+{
+	return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
+}
+
+/**
+ * @brief Send a encapsulated_data message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param seqnr sequence number (starting with 0 on every transmission)
+ * @param data image data bytes
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t* data)
+{
+	mavlink_message_t msg;
+	mavlink_msg_encapsulated_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seqnr, data);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE ENCAPSULATED_DATA UNPACKING
+
+/**
+ * @brief Get field seqnr from encapsulated_data message
+ *
+ * @return sequence number (starting with 0 on every transmission)
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field data from encapsulated_data message
+ *
+ * @return image data bytes
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t), sizeof(uint8_t)*253);
+	return sizeof(uint8_t)*253;
+}
+
+/**
+ * @brief Decode a encapsulated_data message into a struct
+ *
+ * @param msg The message to decode
+ * @param encapsulated_data C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
+{
+	encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
+	mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_global_vision_position_estimate.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING
+
+#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 114
+
+typedef struct __mavlink_global_vision_position_estimate_t 
+{
+    uint64_t usec; ///< Timestamp (milliseconds)
+    float x; ///< Global X position
+    float y; ///< Global Y position
+    float z; ///< Global Z position
+    float roll; ///< Roll angle in rad
+    float pitch; ///< Pitch angle in rad
+    float yaw; ///< Yaw angle in rad
+
+} mavlink_global_vision_position_estimate_t;
+
+
+
+/**
+ * @brief Pack a global_vision_position_estimate 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 usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+    i += put_float_by_index(x, i, msg->payload); // Global X position
+    i += put_float_by_index(y, i, msg->payload); // Global Y position
+    i += put_float_by_index(z, i, msg->payload); // Global Z position
+    i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+    i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+    i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+    return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a global_vision_position_estimate message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+    uint16_t i = 0;
+    msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
+
+    i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+    i += put_float_by_index(x, i, msg->payload); // Global X position
+    i += put_float_by_index(y, i, msg->payload); // Global Y position
+    i += put_float_by_index(z, i, msg->payload); // Global Z position
+    i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+    i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+    i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a global_vision_position_estimate struct into a 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 global_vision_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
+{
+    return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw);
+}
+
+/**
+ * @brief Send a global_vision_position_estimate message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+    mavlink_message_t msg;
+    mavlink_msg_global_vision_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw);
+    mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING
+
+/**
+ * @brief Get field usec from global_vision_position_estimate message
+ *
+ * @return Timestamp (milliseconds)
+ */
+static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg)
+{
+    generic_64bit r;
+    r.b[7] = (msg->payload)[0];
+    r.b[6] = (msg->payload)[1];
+    r.b[5] = (msg->payload)[2];
+    r.b[4] = (msg->payload)[3];
+    r.b[3] = (msg->payload)[4];
+    r.b[2] = (msg->payload)[5];
+    r.b[1] = (msg->payload)[6];
+    r.b[0] = (msg->payload)[7];
+    return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from global_vision_position_estimate message
+ *
+ * @return Global X position
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field y from global_vision_position_estimate message
+ *
+ * @return Global Y position
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field z from global_vision_position_estimate message
+ *
+ * @return Global Z position
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from global_vision_position_estimate message
+ *
+ * @return Roll angle in rad
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from global_vision_position_estimate message
+ *
+ * @return Pitch angle in rad
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from global_vision_position_estimate message
+ *
+ * @return Yaw angle in rad
+ */
+static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
+{
+    generic_32bit r;
+    r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+    r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+    r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+    r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+    return (float)r.f;
+}
+
+/**
+ * @brief Decode a global_vision_position_estimate message into a struct
+ *
+ * @param msg The message to decode
+ * @param global_vision_position_estimate C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
+{
+    global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg);
+    global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg);
+    global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg);
+    global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg);
+    global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg);
+    global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg);
+    global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_available.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,586 @@
+// MESSAGE IMAGE_AVAILABLE PACKING
+
+#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 103
+
+typedef struct __mavlink_image_available_t 
+{
+	uint64_t cam_id; ///< Camera id
+	uint8_t cam_no; ///< Camera # (starts with 0)
+	uint64_t timestamp; ///< Timestamp
+	uint64_t valid_until; ///< Until which timestamp this buffer will stay valid
+	uint32_t img_seq; ///< The image sequence number
+	uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0
+	uint16_t width; ///< Image width
+	uint16_t height; ///< Image height
+	uint16_t depth; ///< Image depth
+	uint8_t channels; ///< Image channels
+	uint32_t key; ///< Shared memory area key
+	uint32_t exposure; ///< Exposure time, in microseconds
+	float gain; ///< Camera gain
+	float roll; ///< Roll angle in rad
+	float pitch; ///< Pitch angle in rad
+	float yaw; ///< Yaw angle in rad
+	float local_z; ///< Local frame Z coordinate (height over ground)
+	float lat; ///< GPS X coordinate
+	float lon; ///< GPS Y coordinate
+	float alt; ///< Global frame altitude
+	float ground_x; ///< Ground truth X
+	float ground_y; ///< Ground truth Y
+	float ground_z; ///< Ground truth Z
+
+} mavlink_image_available_t;
+
+
+
+/**
+ * @brief Pack a image_available 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 cam_id Camera id
+ * @param cam_no Camera # (starts with 0)
+ * @param timestamp Timestamp
+ * @param valid_until Until which timestamp this buffer will stay valid
+ * @param img_seq The image sequence number
+ * @param img_buf_index Position of the image in the buffer, starts with 0
+ * @param width Image width
+ * @param height Image height
+ * @param depth Image depth
+ * @param channels Image channels
+ * @param key Shared memory area key
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
+
+	i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id
+	i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0)
+	i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
+	i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid
+	i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number
+	i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0
+	i += put_uint16_t_by_index(width, i, msg->payload); // Image width
+	i += put_uint16_t_by_index(height, i, msg->payload); // Image height
+	i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth
+	i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels
+	i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key
+	i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
+	i += put_float_by_index(gain, i, msg->payload); // Camera gain
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+	i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
+	i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
+	i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
+	i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
+	i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
+	i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
+	i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a image_available message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param cam_id Camera id
+ * @param cam_no Camera # (starts with 0)
+ * @param timestamp Timestamp
+ * @param valid_until Until which timestamp this buffer will stay valid
+ * @param img_seq The image sequence number
+ * @param img_buf_index Position of the image in the buffer, starts with 0
+ * @param width Image width
+ * @param height Image height
+ * @param depth Image depth
+ * @param channels Image channels
+ * @param key Shared memory area key
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
+
+	i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id
+	i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0)
+	i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
+	i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid
+	i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number
+	i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0
+	i += put_uint16_t_by_index(width, i, msg->payload); // Image width
+	i += put_uint16_t_by_index(height, i, msg->payload); // Image height
+	i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth
+	i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels
+	i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key
+	i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
+	i += put_float_by_index(gain, i, msg->payload); // Camera gain
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+	i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
+	i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
+	i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
+	i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
+	i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
+	i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
+	i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a image_available struct into a 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 image_available C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available)
+{
+	return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z);
+}
+
+/**
+ * @brief Send a image_available message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param cam_id Camera id
+ * @param cam_no Camera # (starts with 0)
+ * @param timestamp Timestamp
+ * @param valid_until Until which timestamp this buffer will stay valid
+ * @param img_seq The image sequence number
+ * @param img_buf_index Position of the image in the buffer, starts with 0
+ * @param width Image width
+ * @param height Image height
+ * @param depth Image depth
+ * @param channels Image channels
+ * @param key Shared memory area key
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE IMAGE_AVAILABLE UNPACKING
+
+/**
+ * @brief Get field cam_id from image_available message
+ *
+ * @return Camera id
+ */
+static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field cam_no from image_available message
+ *
+ * @return Camera # (starts with 0)
+ */
+static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
+}
+
+/**
+ * @brief Get field timestamp from image_available message
+ *
+ * @return Timestamp
+ */
+static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
+	r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
+	r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
+	r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field valid_until from image_available message
+ *
+ * @return Until which timestamp this buffer will stay valid
+ */
+static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[0];
+	r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[1];
+	r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[2];
+	r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[3];
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[4];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[5];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[6];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field img_seq from image_available message
+ *
+ * @return The image sequence number
+ */
+static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field img_buf_index from image_available message
+ *
+ * @return Position of the image in the buffer, starts with 0
+ */
+static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field width from image_available message
+ *
+ * @return Image width
+ */
+static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field height from image_available message
+ *
+ * @return Image height
+ */
+static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field depth from image_available message
+ *
+ * @return Image depth
+ */
+static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field channels from image_available message
+ *
+ * @return Image channels
+ */
+static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Get field key from image_available message
+ *
+ * @return Shared memory area key
+ */
+static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field exposure from image_available message
+ *
+ * @return Exposure time, in microseconds
+ */
+static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field gain from image_available message
+ *
+ * @return Camera gain
+ */
+static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from image_available message
+ *
+ * @return Roll angle in rad
+ */
+static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from image_available message
+ *
+ * @return Pitch angle in rad
+ */
+static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from image_available message
+ *
+ * @return Yaw angle in rad
+ */
+static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field local_z from image_available message
+ *
+ * @return Local frame Z coordinate (height over ground)
+ */
+static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lat from image_available message
+ *
+ * @return GPS X coordinate
+ */
+static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lon from image_available message
+ *
+ * @return GPS Y coordinate
+ */
+static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field alt from image_available message
+ *
+ * @return Global frame altitude
+ */
+static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_x from image_available message
+ *
+ * @return Ground truth X
+ */
+static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_y from image_available message
+ *
+ * @return Ground truth Y
+ */
+static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_z from image_available message
+ *
+ * @return Ground truth Z
+ */
+static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a image_available message into a struct
+ *
+ * @param msg The message to decode
+ * @param image_available C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available)
+{
+	image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg);
+	image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg);
+	image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg);
+	image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg);
+	image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg);
+	image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg);
+	image_available->width = mavlink_msg_image_available_get_width(msg);
+	image_available->height = mavlink_msg_image_available_get_height(msg);
+	image_available->depth = mavlink_msg_image_available_get_depth(msg);
+	image_available->channels = mavlink_msg_image_available_get_channels(msg);
+	image_available->key = mavlink_msg_image_available_get_key(msg);
+	image_available->exposure = mavlink_msg_image_available_get_exposure(msg);
+	image_available->gain = mavlink_msg_image_available_get_gain(msg);
+	image_available->roll = mavlink_msg_image_available_get_roll(msg);
+	image_available->pitch = mavlink_msg_image_available_get_pitch(msg);
+	image_available->yaw = mavlink_msg_image_available_get_yaw(msg);
+	image_available->local_z = mavlink_msg_image_available_get_local_z(msg);
+	image_available->lat = mavlink_msg_image_available_get_lat(msg);
+	image_available->lon = mavlink_msg_image_available_get_lon(msg);
+	image_available->alt = mavlink_msg_image_available_get_alt(msg);
+	image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg);
+	image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg);
+	image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_trigger_control.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,101 @@
+// MESSAGE IMAGE_TRIGGER_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 102
+
+typedef struct __mavlink_image_trigger_control_t 
+{
+	uint8_t enable; ///< 0 to disable, 1 to enable
+
+} mavlink_image_trigger_control_t;
+
+
+
+/**
+ * @brief Pack a image_trigger_control 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 enable 0 to disable, 1 to enable
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enable)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
+
+	i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a image_trigger_control message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param enable 0 to disable, 1 to enable
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enable)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
+
+	i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a image_trigger_control struct into a 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 image_trigger_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control)
+{
+	return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable);
+}
+
+/**
+ * @brief Send a image_trigger_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param enable 0 to disable, 1 to enable
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable)
+{
+	mavlink_message_t msg;
+	mavlink_msg_image_trigger_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enable);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING
+
+/**
+ * @brief Get field enable from image_trigger_control message
+ *
+ * @return 0 to disable, 1 to enable
+ */
+static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Decode a image_trigger_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param image_trigger_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control)
+{
+	image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_image_triggered.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,352 @@
+// MESSAGE IMAGE_TRIGGERED PACKING
+
+#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 101
+
+typedef struct __mavlink_image_triggered_t 
+{
+	uint64_t timestamp; ///< Timestamp
+	uint32_t seq; ///< IMU seq
+	float roll; ///< Roll angle in rad
+	float pitch; ///< Pitch angle in rad
+	float yaw; ///< Yaw angle in rad
+	float local_z; ///< Local frame Z coordinate (height over ground)
+	float lat; ///< GPS X coordinate
+	float lon; ///< GPS Y coordinate
+	float alt; ///< Global frame altitude
+	float ground_x; ///< Ground truth X
+	float ground_y; ///< Ground truth Y
+	float ground_z; ///< Ground truth Z
+
+} mavlink_image_triggered_t;
+
+
+
+/**
+ * @brief Pack a image_triggered 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 timestamp Timestamp
+ * @param seq IMU seq
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
+
+	i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
+	i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+	i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
+	i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
+	i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
+	i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
+	i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
+	i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
+	i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a image_triggered message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param timestamp Timestamp
+ * @param seq IMU seq
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
+
+	i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
+	i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+	i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
+	i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
+	i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
+	i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
+	i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
+	i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
+	i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a image_triggered struct into a 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 image_triggered C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
+{
+	return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z);
+}
+
+/**
+ * @brief Send a image_triggered message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp Timestamp
+ * @param seq IMU seq
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @param local_z Local frame Z coordinate (height over ground)
+ * @param lat GPS X coordinate
+ * @param lon GPS Y coordinate
+ * @param alt Global frame altitude
+ * @param ground_x Ground truth X
+ * @param ground_y Ground truth Y
+ * @param ground_z Ground truth Z
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE IMAGE_TRIGGERED UNPACKING
+
+/**
+ * @brief Get field timestamp from image_triggered message
+ *
+ * @return Timestamp
+ */
+static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field seq from image_triggered message
+ *
+ * @return IMU seq
+ */
+static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (uint32_t)r.i;
+}
+
+/**
+ * @brief Get field roll from image_triggered message
+ *
+ * @return Roll angle in rad
+ */
+static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from image_triggered message
+ *
+ * @return Pitch angle in rad
+ */
+static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from image_triggered message
+ *
+ * @return Yaw angle in rad
+ */
+static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field local_z from image_triggered message
+ *
+ * @return Local frame Z coordinate (height over ground)
+ */
+static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lat from image_triggered message
+ *
+ * @return GPS X coordinate
+ */
+static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field lon from image_triggered message
+ *
+ * @return GPS Y coordinate
+ */
+static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field alt from image_triggered message
+ *
+ * @return Global frame altitude
+ */
+static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_x from image_triggered message
+ *
+ * @return Ground truth X
+ */
+static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_y from image_triggered message
+ *
+ * @return Ground truth Y
+ */
+static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ground_z from image_triggered message
+ *
+ * @return Ground truth Z
+ */
+static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a image_triggered message into a struct
+ *
+ * @param msg The message to decode
+ * @param image_triggered C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered)
+{
+	image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg);
+	image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg);
+	image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg);
+	image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg);
+	image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg);
+	image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg);
+	image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg);
+	image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg);
+	image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg);
+	image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg);
+	image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg);
+	image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_marker.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,236 @@
+// MESSAGE MARKER PACKING
+
+#define MAVLINK_MSG_ID_MARKER 130
+
+typedef struct __mavlink_marker_t 
+{
+	uint16_t id; ///< ID
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float roll; ///< roll orientation
+	float pitch; ///< pitch orientation
+	float yaw; ///< yaw orientation
+
+} mavlink_marker_t;
+
+
+
+/**
+ * @brief Pack a marker 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 id ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param roll roll orientation
+ * @param pitch pitch orientation
+ * @param yaw yaw orientation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MARKER;
+
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(roll, i, msg->payload); // roll orientation
+	i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a marker message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param id ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param roll roll orientation
+ * @param pitch pitch orientation
+ * @param yaw yaw orientation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MARKER;
+
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(roll, i, msg->payload); // roll orientation
+	i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a marker struct into a 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 marker C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
+{
+	return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
+}
+
+/**
+ * @brief Send a marker message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param id ID
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param roll roll orientation
+ * @param pitch pitch orientation
+ * @param yaw yaw orientation
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_marker_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, roll, pitch, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE MARKER UNPACKING
+
+/**
+ * @brief Get field id from marker message
+ *
+ * @return ID
+ */
+static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field x from marker message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from marker message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from marker message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from marker message
+ *
+ * @return roll orientation
+ */
+static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from marker message
+ *
+ * @return pitch orientation
+ */
+static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from marker message
+ *
+ * @return yaw orientation
+ */
+static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a marker message into a struct
+ *
+ * @param msg The message to decode
+ * @param marker C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker)
+{
+	marker->id = mavlink_msg_marker_get_id(msg);
+	marker->x = mavlink_msg_marker_get_x(msg);
+	marker->y = mavlink_msg_marker_get_y(msg);
+	marker->z = mavlink_msg_marker_get_z(msg);
+	marker->roll = mavlink_msg_marker_get_roll(msg);
+	marker->pitch = mavlink_msg_marker_get_pitch(msg);
+	marker->yaw = mavlink_msg_marker_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_pattern_detected.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,160 @@
+// MESSAGE PATTERN_DETECTED PACKING
+
+#define MAVLINK_MSG_ID_PATTERN_DETECTED 160
+
+typedef struct __mavlink_pattern_detected_t 
+{
+	uint8_t type; ///< 0: Pattern, 1: Letter
+	float confidence; ///< Confidence of detection
+	int8_t file[100]; ///< Pattern file name
+	uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes
+
+} mavlink_pattern_detected_t;
+
+#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100
+
+
+/**
+ * @brief Pack a pattern_detected 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 0: Pattern, 1: Letter
+ * @param confidence Confidence of detection
+ * @param file Pattern file name
+ * @param detected Accepted as true detection, 0 no, 1 yes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter
+	i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection
+	i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name
+	i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a pattern_detected message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param type 0: Pattern, 1: Letter
+ * @param confidence Confidence of detection
+ * @param file Pattern file name
+ * @param detected Accepted as true detection, 0 no, 1 yes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter
+	i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection
+	i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name
+	i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a pattern_detected struct into a 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 pattern_detected C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected)
+{
+	return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
+}
+
+/**
+ * @brief Send a pattern_detected message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type 0: Pattern, 1: Letter
+ * @param confidence Confidence of detection
+ * @param file Pattern file name
+ * @param detected Accepted as true detection, 0 no, 1 yes
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
+{
+	mavlink_message_t msg;
+	mavlink_msg_pattern_detected_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, confidence, file, detected);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE PATTERN_DETECTED UNPACKING
+
+/**
+ * @brief Get field type from pattern_detected message
+ *
+ * @return 0: Pattern, 1: Letter
+ */
+static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field confidence from pattern_detected message
+ *
+ * @return Confidence of detection
+ */
+static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field file from pattern_detected message
+ *
+ * @return Pattern file name
+ */
+static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(float), 100);
+	return 100;
+}
+
+/**
+ * @brief Get field detected from pattern_detected message
+ *
+ * @return Accepted as true detection, 0 no, 1 yes
+ */
+static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+100)[0];
+}
+
+/**
+ * @brief Decode a pattern_detected message into a struct
+ *
+ * @param msg The message to decode
+ * @param pattern_detected C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected)
+{
+	pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg);
+	pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg);
+	mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file);
+	pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_point_of_interest.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,241 @@
+// MESSAGE POINT_OF_INTEREST PACKING
+
+#define MAVLINK_MSG_ID_POINT_OF_INTEREST 161
+
+typedef struct __mavlink_point_of_interest_t 
+{
+	uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	uint8_t coordinate_system; ///< 0: global, 1:local
+	uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
+	float x; ///< X Position
+	float y; ///< Y Position
+	float z; ///< Z Position
+	int8_t name[25]; ///< POI name
+
+} mavlink_point_of_interest_t;
+
+#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 25
+
+
+/**
+ * @brief Pack a point_of_interest 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 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param name POI name
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
+	i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
+	i += put_float_by_index(x, i, msg->payload); // X Position
+	i += put_float_by_index(y, i, msg->payload); // Y Position
+	i += put_float_by_index(z, i, msg->payload); // Z Position
+	i += put_array_by_index(name, 25, i, msg->payload); // POI name
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a point_of_interest message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param name POI name
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
+	i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
+	i += put_float_by_index(x, i, msg->payload); // X Position
+	i += put_float_by_index(y, i, msg->payload); // Y Position
+	i += put_float_by_index(z, i, msg->payload); // Z Position
+	i += put_array_by_index(name, 25, i, msg->payload); // POI name
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a point_of_interest struct into a 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 point_of_interest C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
+{
+	return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
+}
+
+/**
+ * @brief Send a point_of_interest message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param name POI name
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
+{
+	mavlink_message_t msg;
+	mavlink_msg_point_of_interest_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, x, y, z, name);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POINT_OF_INTEREST UNPACKING
+
+/**
+ * @brief Get field type from point_of_interest message
+ *
+ * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ */
+static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field color from point_of_interest message
+ *
+ * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ */
+static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field coordinate_system from point_of_interest message
+ *
+ * @return 0: global, 1:local
+ */
+static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field timeout from point_of_interest message
+ *
+ * @return 0: no timeout, >1: timeout in seconds
+ */
+static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field x from point_of_interest message
+ *
+ * @return X Position
+ */
+static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from point_of_interest message
+ *
+ * @return Y Position
+ */
+static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from point_of_interest message
+ *
+ * @return Z Position
+ */
+static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field name from point_of_interest message
+ *
+ * @return POI name
+ */
+static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float), 25);
+	return 25;
+}
+
+/**
+ * @brief Decode a point_of_interest message into a struct
+ *
+ * @param msg The message to decode
+ * @param point_of_interest C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest)
+{
+	point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg);
+	point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg);
+	point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg);
+	point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg);
+	point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg);
+	point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg);
+	point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg);
+	mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,307 @@
+// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING
+
+#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 162
+
+typedef struct __mavlink_point_of_interest_connection_t 
+{
+	uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	uint8_t coordinate_system; ///< 0: global, 1:local
+	uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
+	float xp1; ///< X1 Position
+	float yp1; ///< Y1 Position
+	float zp1; ///< Z1 Position
+	float xp2; ///< X2 Position
+	float yp2; ///< Y2 Position
+	float zp2; ///< Z2 Position
+	int8_t name[25]; ///< POI connection name
+
+} mavlink_point_of_interest_connection_t;
+
+#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 25
+
+
+/**
+ * @brief Pack a point_of_interest_connection 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 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param xp1 X1 Position
+ * @param yp1 Y1 Position
+ * @param zp1 Z1 Position
+ * @param xp2 X2 Position
+ * @param yp2 Y2 Position
+ * @param zp2 Z2 Position
+ * @param name POI connection name
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
+	i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
+	i += put_float_by_index(xp1, i, msg->payload); // X1 Position
+	i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
+	i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
+	i += put_float_by_index(xp2, i, msg->payload); // X2 Position
+	i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
+	i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
+	i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a point_of_interest_connection message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param xp1 X1 Position
+ * @param yp1 Y1 Position
+ * @param zp1 Z1 Position
+ * @param xp2 X2 Position
+ * @param yp2 Y2 Position
+ * @param zp2 Z2 Position
+ * @param name POI connection name
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
+
+	i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+	i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+	i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
+	i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
+	i += put_float_by_index(xp1, i, msg->payload); // X1 Position
+	i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
+	i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
+	i += put_float_by_index(xp2, i, msg->payload); // X2 Position
+	i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
+	i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
+	i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a point_of_interest_connection struct into a 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 point_of_interest_connection C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
+{
+	return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
+}
+
+/**
+ * @brief Send a point_of_interest_connection message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ * @param coordinate_system 0: global, 1:local
+ * @param timeout 0: no timeout, >1: timeout in seconds
+ * @param xp1 X1 Position
+ * @param yp1 Y1 Position
+ * @param zp1 Z1 Position
+ * @param xp2 X2 Position
+ * @param yp2 Y2 Position
+ * @param zp2 Z2 Position
+ * @param name POI connection name
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
+{
+	mavlink_message_t msg;
+	mavlink_msg_point_of_interest_connection_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, xp1, yp1, zp1, xp2, yp2, zp2, name);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING
+
+/**
+ * @brief Get field type from point_of_interest_connection message
+ *
+ * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
+ */
+static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field color from point_of_interest_connection message
+ *
+ * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
+ */
+static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field coordinate_system from point_of_interest_connection message
+ *
+ * @return 0: global, 1:local
+ */
+static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field timeout from point_of_interest_connection message
+ *
+ * @return 0: no timeout, >1: timeout in seconds
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field xp1 from point_of_interest_connection message
+ *
+ * @return X1 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yp1 from point_of_interest_connection message
+ *
+ * @return Y1 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field zp1 from point_of_interest_connection message
+ *
+ * @return Z1 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field xp2 from point_of_interest_connection message
+ *
+ * @return X2 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yp2 from point_of_interest_connection message
+ *
+ * @return Y2 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field zp2 from point_of_interest_connection message
+ *
+ * @return Z2 Position
+ */
+static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field name from point_of_interest_connection message
+ *
+ * @return POI connection name
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float), 25);
+	return 25;
+}
+
+/**
+ * @brief Decode a point_of_interest_connection message into a struct
+ *
+ * @param msg The message to decode
+ * @param point_of_interest_connection C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection)
+{
+	point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg);
+	point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg);
+	point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg);
+	point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg);
+	point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg);
+	point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg);
+	point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg);
+	point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg);
+	point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg);
+	point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg);
+	mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_offset_set.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,206 @@
+// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING
+
+#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 154
+
+typedef struct __mavlink_position_control_offset_set_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	float x; ///< x position offset
+	float y; ///< y position offset
+	float z; ///< z position offset
+	float yaw; ///< yaw orientation offset in radians, 0 = NORTH
+
+} mavlink_position_control_offset_set_t;
+
+
+
+/**
+ * @brief Pack a position_control_offset_set 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 target_system System ID
+ * @param target_component Component ID
+ * @param x x position offset
+ * @param y y position offset
+ * @param z z position offset
+ * @param yaw yaw orientation offset in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(x, i, msg->payload); // x position offset
+	i += put_float_by_index(y, i, msg->payload); // y position offset
+	i += put_float_by_index(z, i, msg->payload); // z position offset
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a position_control_offset_set message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param x x position offset
+ * @param y y position offset
+ * @param z z position offset
+ * @param yaw yaw orientation offset in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_offset_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_float_by_index(x, i, msg->payload); // x position offset
+	i += put_float_by_index(y, i, msg->payload); // y position offset
+	i += put_float_by_index(z, i, msg->payload); // z position offset
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a position_control_offset_set struct into a 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 position_control_offset_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set)
+{
+	return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw);
+}
+
+/**
+ * @brief Send a position_control_offset_set message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param x x position offset
+ * @param y y position offset
+ * @param z z position offset
+ * @param yaw yaw orientation offset in radians, 0 = NORTH
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_position_control_offset_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING
+
+/**
+ * @brief Get field target_system from position_control_offset_set message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from position_control_offset_set message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field x from position_control_offset_set message
+ *
+ * @return x position offset
+ */
+static inline float mavlink_msg_position_control_offset_set_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from position_control_offset_set message
+ *
+ * @return y position offset
+ */
+static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from position_control_offset_set message
+ *
+ * @return z position offset
+ */
+static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from position_control_offset_set message
+ *
+ * @return yaw orientation offset in radians, 0 = NORTH
+ */
+static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a position_control_offset_set message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_control_offset_set C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set)
+{
+	position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg);
+	position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg);
+	position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg);
+	position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg);
+	position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg);
+	position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,192 @@
+// MESSAGE POSITION_CONTROL_SETPOINT PACKING
+
+#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 121
+
+typedef struct __mavlink_position_control_setpoint_t 
+{
+	uint16_t id; ///< ID of waypoint, 0 for plain position
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float yaw; ///< yaw orientation in radians, 0 = NORTH
+
+} mavlink_position_control_setpoint_t;
+
+
+
+/**
+ * @brief Pack a position_control_setpoint 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 id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
+
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a position_control_setpoint message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
+
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a position_control_setpoint struct into a 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 position_control_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint)
+{
+	return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
+}
+
+/**
+ * @brief Send a position_control_setpoint message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_position_control_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING
+
+/**
+ * @brief Get field id from position_control_setpoint message
+ *
+ * @return ID of waypoint, 0 for plain position
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field x from position_control_setpoint message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from position_control_setpoint message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from position_control_setpoint message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from position_control_setpoint message
+ *
+ * @return yaw orientation in radians, 0 = NORTH
+ */
+static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a position_control_setpoint message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_control_setpoint C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint)
+{
+	position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg);
+	position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg);
+	position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg);
+	position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg);
+	position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,226 @@
+// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING
+
+#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 120
+
+typedef struct __mavlink_position_control_setpoint_set_t 
+{
+	uint8_t target_system; ///< System ID
+	uint8_t target_component; ///< Component ID
+	uint16_t id; ///< ID of waypoint, 0 for plain position
+	float x; ///< x position
+	float y; ///< y position
+	float z; ///< z position
+	float yaw; ///< yaw orientation in radians, 0 = NORTH
+
+} mavlink_position_control_setpoint_set_t;
+
+
+
+/**
+ * @brief Pack a position_control_setpoint_set 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 target_system System ID
+ * @param target_component Component ID
+ * @param id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a position_control_setpoint_set message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
+
+	i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
+	i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
+	i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
+	i += put_float_by_index(x, i, msg->payload); // x position
+	i += put_float_by_index(y, i, msg->payload); // y position
+	i += put_float_by_index(z, i, msg->payload); // z position
+	i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a position_control_setpoint_set struct into a 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 position_control_setpoint_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
+{
+	return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw);
+}
+
+/**
+ * @brief Send a position_control_setpoint_set message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param id ID of waypoint, 0 for plain position
+ * @param x x position
+ * @param y y position
+ * @param z z position
+ * @param yaw yaw orientation in radians, 0 = NORTH
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_position_control_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, id, x, y, z, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING
+
+/**
+ * @brief Get field target_system from position_control_setpoint_set message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field target_component from position_control_setpoint_set message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field id from position_control_setpoint_set message
+ *
+ * @return ID of waypoint, 0 for plain position
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field x from position_control_setpoint_set message
+ *
+ * @return x position
+ */
+static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from position_control_setpoint_set message
+ *
+ * @return y position
+ */
+static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from position_control_setpoint_set message
+ *
+ * @return z position
+ */
+static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from position_control_setpoint_set message
+ *
+ * @return yaw orientation in radians, 0 = NORTH
+ */
+static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a position_control_setpoint_set message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_control_setpoint_set C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
+{
+	position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg);
+	position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg);
+	position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg);
+	position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg);
+	position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg);
+	position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg);
+	position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_raw_aux.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,226 @@
+// MESSAGE RAW_AUX PACKING
+
+#define MAVLINK_MSG_ID_RAW_AUX 141
+
+typedef struct __mavlink_raw_aux_t 
+{
+	uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6)
+	uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2)
+	uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1)
+	uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3)
+	uint16_t vbat; ///< Battery voltage
+	int16_t temp; ///< Temperature (degrees celcius)
+	int32_t baro; ///< Barometric pressure (hecto Pascal)
+
+} mavlink_raw_aux_t;
+
+
+
+/**
+ * @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
+ * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
+ * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
+ * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
+ * @param vbat Battery voltage
+ * @param temp Temperature (degrees celcius)
+ * @param baro Barometric pressure (hecto Pascal)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
+
+	i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6)
+	i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2)
+	i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1)
+	i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3)
+	i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage
+	i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius)
+	i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a raw_aux message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
+ * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
+ * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
+ * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
+ * @param vbat Battery voltage
+ * @param temp Temperature (degrees celcius)
+ * @param baro Barometric pressure (hecto Pascal)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
+
+	i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6)
+	i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2)
+	i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1)
+	i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3)
+	i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage
+	i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius)
+	i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a raw_aux struct into a 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 raw_aux C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
+{
+	return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
+}
+
+/**
+ * @brief Send a raw_aux message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
+ * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
+ * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
+ * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
+ * @param vbat Battery voltage
+ * @param temp Temperature (degrees celcius)
+ * @param baro Barometric pressure (hecto Pascal)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
+{
+	mavlink_message_t msg;
+	mavlink_msg_raw_aux_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, adc1, adc2, adc3, adc4, vbat, temp, baro);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RAW_AUX UNPACKING
+
+/**
+ * @brief Get field adc1 from raw_aux message
+ *
+ * @return ADC1 (J405 ADC3, LPC2148 AD0.6)
+ */
+static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field adc2 from raw_aux message
+ *
+ * @return ADC2 (J405 ADC5, LPC2148 AD0.2)
+ */
+static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field adc3 from raw_aux message
+ *
+ * @return ADC3 (J405 ADC6, LPC2148 AD0.1)
+ */
+static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field adc4 from raw_aux message
+ *
+ * @return ADC4 (J405 ADC7, LPC2148 AD1.3)
+ */
+static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field vbat from raw_aux message
+ *
+ * @return Battery voltage
+ */
+static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field temp from raw_aux message
+ *
+ * @return Temperature (degrees celcius)
+ */
+static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field baro from raw_aux message
+ *
+ * @return Barometric pressure (hecto Pascal)
+ */
+static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Decode a raw_aux message into a struct
+ *
+ * @param msg The message to decode
+ * @param raw_aux C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux)
+{
+	raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg);
+	raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg);
+	raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg);
+	raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg);
+	raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg);
+	raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg);
+	raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_set_cam_shutter.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,197 @@
+// MESSAGE SET_CAM_SHUTTER PACKING
+
+#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 190
+
+typedef struct __mavlink_set_cam_shutter_t 
+{
+	uint8_t cam_no; ///< Camera id
+	uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual
+	uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly
+	uint16_t interval; ///< Shutter interval, in microseconds
+	uint16_t exposure; ///< Exposure time, in microseconds
+	float gain; ///< Camera gain
+
+} mavlink_set_cam_shutter_t;
+
+
+
+/**
+ * @brief Pack a set_cam_shutter 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 cam_no Camera id
+ * @param cam_mode Camera mode: 0 = auto, 1 = manual
+ * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
+ * @param interval Shutter interval, in microseconds
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
+
+	i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
+	i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
+	i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
+	i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
+	i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
+	i += put_float_by_index(gain, i, msg->payload); // Camera gain
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a set_cam_shutter message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param cam_no Camera id
+ * @param cam_mode Camera mode: 0 = auto, 1 = manual
+ * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
+ * @param interval Shutter interval, in microseconds
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
+
+	i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
+	i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
+	i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
+	i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
+	i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
+	i += put_float_by_index(gain, i, msg->payload); // Camera gain
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a set_cam_shutter struct into a 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 set_cam_shutter C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
+{
+	return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
+}
+
+/**
+ * @brief Send a set_cam_shutter message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param cam_no Camera id
+ * @param cam_mode Camera mode: 0 = auto, 1 = manual
+ * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
+ * @param interval Shutter interval, in microseconds
+ * @param exposure Exposure time, in microseconds
+ * @param gain Camera gain
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
+{
+	mavlink_message_t msg;
+	mavlink_msg_set_cam_shutter_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SET_CAM_SHUTTER UNPACKING
+
+/**
+ * @brief Get field cam_no from set_cam_shutter message
+ *
+ * @return Camera id
+ */
+static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field cam_mode from set_cam_shutter message
+ *
+ * @return Camera mode: 0 = auto, 1 = manual
+ */
+static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field trigger_pin from set_cam_shutter message
+ *
+ * @return Trigger pin, 0-3 for PtGrey FireFly
+ */
+static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field interval from set_cam_shutter message
+ *
+ * @return Shutter interval, in microseconds
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field exposure from set_cam_shutter message
+ *
+ * @return Exposure time, in microseconds
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field gain from set_cam_shutter message
+ *
+ * @return Camera gain
+ */
+static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a set_cam_shutter message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_cam_shutter C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter)
+{
+	set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg);
+	set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg);
+	set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg);
+	set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg);
+	set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg);
+	set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE VICON_POSITION_ESTIMATE PACKING
+
+#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 112
+
+typedef struct __mavlink_vicon_position_estimate_t 
+{
+	uint64_t usec; ///< Timestamp (milliseconds)
+	float x; ///< Global X position
+	float y; ///< Global Y position
+	float z; ///< Global Z position
+	float roll; ///< Roll angle in rad
+	float pitch; ///< Pitch angle in rad
+	float yaw; ///< Yaw angle in rad
+
+} mavlink_vicon_position_estimate_t;
+
+
+
+/**
+ * @brief Pack a vicon_position_estimate 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 usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X position
+	i += put_float_by_index(y, i, msg->payload); // Global Y position
+	i += put_float_by_index(z, i, msg->payload); // Global Z position
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a vicon_position_estimate message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X position
+	i += put_float_by_index(y, i, msg->payload); // Global Y position
+	i += put_float_by_index(z, i, msg->payload); // Global Z position
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a vicon_position_estimate struct into a 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 vicon_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
+{
+	return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
+}
+
+/**
+ * @brief Send a vicon_position_estimate message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_vicon_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE VICON_POSITION_ESTIMATE UNPACKING
+
+/**
+ * @brief Get field usec from vicon_position_estimate message
+ *
+ * @return Timestamp (milliseconds)
+ */
+static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from vicon_position_estimate message
+ *
+ * @return Global X position
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from vicon_position_estimate message
+ *
+ * @return Global Y position
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from vicon_position_estimate message
+ *
+ * @return Global Z position
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from vicon_position_estimate message
+ *
+ * @return Roll angle in rad
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from vicon_position_estimate message
+ *
+ * @return Pitch angle in rad
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from vicon_position_estimate message
+ *
+ * @return Yaw angle in rad
+ */
+static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a vicon_position_estimate message into a struct
+ *
+ * @param msg The message to decode
+ * @param vicon_position_estimate C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate)
+{
+	vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg);
+	vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg);
+	vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg);
+	vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg);
+	vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg);
+	vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg);
+	vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vision_position_estimate.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE VISION_POSITION_ESTIMATE PACKING
+
+#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 111
+
+typedef struct __mavlink_vision_position_estimate_t 
+{
+	uint64_t usec; ///< Timestamp (milliseconds)
+	float x; ///< Global X position
+	float y; ///< Global Y position
+	float z; ///< Global Z position
+	float roll; ///< Roll angle in rad
+	float pitch; ///< Pitch angle in rad
+	float yaw; ///< Yaw angle in rad
+
+} mavlink_vision_position_estimate_t;
+
+
+
+/**
+ * @brief Pack a vision_position_estimate 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 usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X position
+	i += put_float_by_index(y, i, msg->payload); // Global Y position
+	i += put_float_by_index(z, i, msg->payload); // Global Z position
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a vision_position_estimate message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X position
+	i += put_float_by_index(y, i, msg->payload); // Global Y position
+	i += put_float_by_index(z, i, msg->payload); // Global Z position
+	i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a vision_position_estimate struct into a 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 vision_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
+{
+	return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
+}
+
+/**
+ * @brief Send a vision_position_estimate message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X position
+ * @param y Global Y position
+ * @param z Global Z position
+ * @param roll Roll angle in rad
+ * @param pitch Pitch angle in rad
+ * @param yaw Yaw angle in rad
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_vision_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE VISION_POSITION_ESTIMATE UNPACKING
+
+/**
+ * @brief Get field usec from vision_position_estimate message
+ *
+ * @return Timestamp (milliseconds)
+ */
+static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from vision_position_estimate message
+ *
+ * @return Global X position
+ */
+static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from vision_position_estimate message
+ *
+ * @return Global Y position
+ */
+static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from vision_position_estimate message
+ *
+ * @return Global Z position
+ */
+static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from vision_position_estimate message
+ *
+ * @return Roll angle in rad
+ */
+static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from vision_position_estimate message
+ *
+ * @return Pitch angle in rad
+ */
+static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from vision_position_estimate message
+ *
+ * @return Yaw angle in rad
+ */
+static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a vision_position_estimate message into a struct
+ *
+ * @param msg The message to decode
+ * @param vision_position_estimate C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
+{
+	vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);
+	vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg);
+	vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg);
+	vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg);
+	vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg);
+	vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg);
+	vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_vision_speed_estimate.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,176 @@
+// MESSAGE VISION_SPEED_ESTIMATE PACKING
+
+#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 113
+
+typedef struct __mavlink_vision_speed_estimate_t 
+{
+	uint64_t usec; ///< Timestamp (milliseconds)
+	float x; ///< Global X speed
+	float y; ///< Global Y speed
+	float z; ///< Global Z speed
+
+} mavlink_vision_speed_estimate_t;
+
+
+
+/**
+ * @brief Pack a vision_speed_estimate 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 usec Timestamp (milliseconds)
+ * @param x Global X speed
+ * @param y Global Y speed
+ * @param z Global Z speed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X speed
+	i += put_float_by_index(y, i, msg->payload); // Global Y speed
+	i += put_float_by_index(z, i, msg->payload); // Global Z speed
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a vision_speed_estimate message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X speed
+ * @param y Global Y speed
+ * @param z Global Z speed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
+	i += put_float_by_index(x, i, msg->payload); // Global X speed
+	i += put_float_by_index(y, i, msg->payload); // Global Y speed
+	i += put_float_by_index(z, i, msg->payload); // Global Z speed
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a vision_speed_estimate struct into a 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 vision_speed_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
+{
+	return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
+}
+
+/**
+ * @brief Send a vision_speed_estimate message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (milliseconds)
+ * @param x Global X speed
+ * @param y Global Y speed
+ * @param z Global Z speed
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
+{
+	mavlink_message_t msg;
+	mavlink_msg_vision_speed_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE VISION_SPEED_ESTIMATE UNPACKING
+
+/**
+ * @brief Get field usec from vision_speed_estimate message
+ *
+ * @return Timestamp (milliseconds)
+ */
+static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from vision_speed_estimate message
+ *
+ * @return Global X speed
+ */
+static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from vision_speed_estimate message
+ *
+ * @return Global Y speed
+ */
+static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from vision_speed_estimate message
+ *
+ * @return Global Z speed
+ */
+static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a vision_speed_estimate message into a struct
+ *
+ * @param msg The message to decode
+ * @param vision_speed_estimate C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
+{
+	vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
+	vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
+	vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
+	vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_visual_odometry.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,268 @@
+// MESSAGE VISUAL_ODOMETRY PACKING
+
+#define MAVLINK_MSG_ID_VISUAL_ODOMETRY 180
+
+typedef struct __mavlink_visual_odometry_t 
+{
+	uint64_t frame1_time_us; ///< Time at which frame 1 was captured (in microseconds since unix epoch)
+	uint64_t frame2_time_us; ///< Time at which frame 2 was captured (in microseconds since unix epoch)
+	float x; ///< Relative X position
+	float y; ///< Relative Y position
+	float z; ///< Relative Z position
+	float roll; ///< Relative roll angle in rad
+	float pitch; ///< Relative pitch angle in rad
+	float yaw; ///< Relative yaw angle in rad
+
+} mavlink_visual_odometry_t;
+
+
+
+/**
+ * @brief Pack a visual_odometry 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 frame1_time_us Time at which frame 1 was captured (in microseconds since unix epoch)
+ * @param frame2_time_us Time at which frame 2 was captured (in microseconds since unix epoch)
+ * @param x Relative X position
+ * @param y Relative Y position
+ * @param z Relative Z position
+ * @param roll Relative roll angle in rad
+ * @param pitch Relative pitch angle in rad
+ * @param yaw Relative yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_visual_odometry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t frame1_time_us, uint64_t frame2_time_us, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISUAL_ODOMETRY;
+
+	i += put_uint64_t_by_index(frame1_time_us, i, msg->payload); // Time at which frame 1 was captured (in microseconds since unix epoch)
+	i += put_uint64_t_by_index(frame2_time_us, i, msg->payload); // Time at which frame 2 was captured (in microseconds since unix epoch)
+	i += put_float_by_index(x, i, msg->payload); // Relative X position
+	i += put_float_by_index(y, i, msg->payload); // Relative Y position
+	i += put_float_by_index(z, i, msg->payload); // Relative Z position
+	i += put_float_by_index(roll, i, msg->payload); // Relative roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Relative pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Relative yaw angle in rad
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a visual_odometry message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param frame1_time_us Time at which frame 1 was captured (in microseconds since unix epoch)
+ * @param frame2_time_us Time at which frame 2 was captured (in microseconds since unix epoch)
+ * @param x Relative X position
+ * @param y Relative Y position
+ * @param z Relative Z position
+ * @param roll Relative roll angle in rad
+ * @param pitch Relative pitch angle in rad
+ * @param yaw Relative yaw angle in rad
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_visual_odometry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t frame1_time_us, uint64_t frame2_time_us, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_VISUAL_ODOMETRY;
+
+	i += put_uint64_t_by_index(frame1_time_us, i, msg->payload); // Time at which frame 1 was captured (in microseconds since unix epoch)
+	i += put_uint64_t_by_index(frame2_time_us, i, msg->payload); // Time at which frame 2 was captured (in microseconds since unix epoch)
+	i += put_float_by_index(x, i, msg->payload); // Relative X position
+	i += put_float_by_index(y, i, msg->payload); // Relative Y position
+	i += put_float_by_index(z, i, msg->payload); // Relative Z position
+	i += put_float_by_index(roll, i, msg->payload); // Relative roll angle in rad
+	i += put_float_by_index(pitch, i, msg->payload); // Relative pitch angle in rad
+	i += put_float_by_index(yaw, i, msg->payload); // Relative yaw angle in rad
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a visual_odometry struct into a 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 visual_odometry C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_visual_odometry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_visual_odometry_t* visual_odometry)
+{
+	return mavlink_msg_visual_odometry_pack(system_id, component_id, msg, visual_odometry->frame1_time_us, visual_odometry->frame2_time_us, visual_odometry->x, visual_odometry->y, visual_odometry->z, visual_odometry->roll, visual_odometry->pitch, visual_odometry->yaw);
+}
+
+/**
+ * @brief Send a visual_odometry message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param frame1_time_us Time at which frame 1 was captured (in microseconds since unix epoch)
+ * @param frame2_time_us Time at which frame 2 was captured (in microseconds since unix epoch)
+ * @param x Relative X position
+ * @param y Relative Y position
+ * @param z Relative Z position
+ * @param roll Relative roll angle in rad
+ * @param pitch Relative pitch angle in rad
+ * @param yaw Relative yaw angle in rad
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_visual_odometry_send(mavlink_channel_t chan, uint64_t frame1_time_us, uint64_t frame2_time_us, float x, float y, float z, float roll, float pitch, float yaw)
+{
+	mavlink_message_t msg;
+	mavlink_msg_visual_odometry_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, frame1_time_us, frame2_time_us, x, y, z, roll, pitch, yaw);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE VISUAL_ODOMETRY UNPACKING
+
+/**
+ * @brief Get field frame1_time_us from visual_odometry message
+ *
+ * @return Time at which frame 1 was captured (in microseconds since unix epoch)
+ */
+static inline uint64_t mavlink_msg_visual_odometry_get_frame1_time_us(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field frame2_time_us from visual_odometry message
+ *
+ * @return Time at which frame 2 was captured (in microseconds since unix epoch)
+ */
+static inline uint64_t mavlink_msg_visual_odometry_get_frame2_time_us(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[6] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[5] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[4] = (msg->payload+sizeof(uint64_t))[3];
+	r.b[3] = (msg->payload+sizeof(uint64_t))[4];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[5];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[6];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field x from visual_odometry message
+ *
+ * @return Relative X position
+ */
+static inline float mavlink_msg_visual_odometry_get_x(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field y from visual_odometry message
+ *
+ * @return Relative Y position
+ */
+static inline float mavlink_msg_visual_odometry_get_y(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field z from visual_odometry message
+ *
+ * @return Relative Z position
+ */
+static inline float mavlink_msg_visual_odometry_get_z(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field roll from visual_odometry message
+ *
+ * @return Relative roll angle in rad
+ */
+static inline float mavlink_msg_visual_odometry_get_roll(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field pitch from visual_odometry message
+ *
+ * @return Relative pitch angle in rad
+ */
+static inline float mavlink_msg_visual_odometry_get_pitch(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field yaw from visual_odometry message
+ *
+ * @return Relative yaw angle in rad
+ */
+static inline float mavlink_msg_visual_odometry_get_yaw(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a visual_odometry message into a struct
+ *
+ * @param msg The message to decode
+ * @param visual_odometry C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_visual_odometry_decode(const mavlink_message_t* msg, mavlink_visual_odometry_t* visual_odometry)
+{
+	visual_odometry->frame1_time_us = mavlink_msg_visual_odometry_get_frame1_time_us(msg);
+	visual_odometry->frame2_time_us = mavlink_msg_visual_odometry_get_frame2_time_us(msg);
+	visual_odometry->x = mavlink_msg_visual_odometry_get_x(msg);
+	visual_odometry->y = mavlink_msg_visual_odometry_get_y(msg);
+	visual_odometry->z = mavlink_msg_visual_odometry_get_z(msg);
+	visual_odometry->roll = mavlink_msg_visual_odometry_get_roll(msg);
+	visual_odometry->pitch = mavlink_msg_visual_odometry_get_pitch(msg);
+	visual_odometry->yaw = mavlink_msg_visual_odometry_get_yaw(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,158 @@
+// MESSAGE WATCHDOG_COMMAND PACKING
+
+#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 153
+
+typedef struct __mavlink_watchdog_command_t 
+{
+	uint8_t target_system_id; ///< Target system ID
+	uint16_t watchdog_id; ///< Watchdog ID
+	uint16_t process_id; ///< Process ID
+	uint8_t command_id; ///< Command ID
+
+} mavlink_watchdog_command_t;
+
+
+
+/**
+ * @brief Pack a watchdog_command 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 target_system_id Target system ID
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param command_id Command ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
+
+	i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a watchdog_command message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system_id Target system ID
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param command_id Command ID
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
+
+	i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a watchdog_command struct into a 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 watchdog_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
+{
+	return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
+}
+
+/**
+ * @brief Send a watchdog_command message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system_id Target system ID
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param command_id Command ID
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
+{
+	mavlink_message_t msg;
+	mavlink_msg_watchdog_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system_id, watchdog_id, process_id, command_id);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WATCHDOG_COMMAND UNPACKING
+
+/**
+ * @brief Get field target_system_id from watchdog_command message
+ *
+ * @return Target system ID
+ */
+static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field watchdog_id from watchdog_command message
+ *
+ * @return Watchdog ID
+ */
+static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field process_id from watchdog_command message
+ *
+ * @return Process ID
+ */
+static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field command_id from watchdog_command message
+ *
+ * @return Command ID
+ */
+static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Decode a watchdog_command message into a struct
+ *
+ * @param msg The message to decode
+ * @param watchdog_command C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command)
+{
+	watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg);
+	watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg);
+	watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg);
+	watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,124 @@
+// MESSAGE WATCHDOG_HEARTBEAT PACKING
+
+#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 150
+
+typedef struct __mavlink_watchdog_heartbeat_t 
+{
+	uint16_t watchdog_id; ///< Watchdog ID
+	uint16_t process_count; ///< Number of processes
+
+} mavlink_watchdog_heartbeat_t;
+
+
+
+/**
+ * @brief Pack a watchdog_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 watchdog_id Watchdog ID
+ * @param process_count Number of processes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a watchdog_heartbeat message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param watchdog_id Watchdog ID
+ * @param process_count Number of processes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a watchdog_heartbeat struct into a 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 watchdog_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
+{
+	return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
+}
+
+/**
+ * @brief Send a watchdog_heartbeat message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param watchdog_id Watchdog ID
+ * @param process_count Number of processes
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
+{
+	mavlink_message_t msg;
+	mavlink_msg_watchdog_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_count);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WATCHDOG_HEARTBEAT UNPACKING
+
+/**
+ * @brief Get field watchdog_id from watchdog_heartbeat message
+ *
+ * @return Watchdog ID
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field process_count from watchdog_heartbeat message
+ *
+ * @return Number of processes
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a watchdog_heartbeat message into a struct
+ *
+ * @param msg The message to decode
+ * @param watchdog_heartbeat C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
+{
+	watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg);
+	watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_info.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,186 @@
+// MESSAGE WATCHDOG_PROCESS_INFO PACKING
+
+#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 151
+
+typedef struct __mavlink_watchdog_process_info_t 
+{
+	uint16_t watchdog_id; ///< Watchdog ID
+	uint16_t process_id; ///< Process ID
+	int8_t name[100]; ///< Process name
+	int8_t arguments[147]; ///< Process arguments
+	int32_t timeout; ///< Timeout (seconds)
+
+} mavlink_watchdog_process_info_t;
+
+#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100
+#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147
+
+
+/**
+ * @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param name Process name
+ * @param arguments Process arguments
+ * @param timeout Timeout (seconds)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_array_by_index(name, 100, i, msg->payload); // Process name
+	i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
+	i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a watchdog_process_info message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param name Process name
+ * @param arguments Process arguments
+ * @param timeout Timeout (seconds)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_array_by_index(name, 100, i, msg->payload); // Process name
+	i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
+	i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a watchdog_process_info struct into a 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 watchdog_process_info C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
+{
+	return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
+}
+
+/**
+ * @brief Send a watchdog_process_info message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param name Process name
+ * @param arguments Process arguments
+ * @param timeout Timeout (seconds)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
+{
+	mavlink_message_t msg;
+	mavlink_msg_watchdog_process_info_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, name, arguments, timeout);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING
+
+/**
+ * @brief Get field watchdog_id from watchdog_process_info message
+ *
+ * @return Watchdog ID
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field process_id from watchdog_process_info message
+ *
+ * @return Process ID
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field name from watchdog_process_info message
+ *
+ * @return Process name
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t), 100);
+	return 100;
+}
+
+/**
+ * @brief Get field arguments from watchdog_process_info message
+ *
+ * @return Process arguments
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, int8_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100, 147);
+	return 147;
+}
+
+/**
+ * @brief Get field timeout from watchdog_process_info message
+ *
+ * @return Timeout (seconds)
+ */
+static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Decode a watchdog_process_info message into a struct
+ *
+ * @param msg The message to decode
+ * @param watchdog_process_info C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info)
+{
+	watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg);
+	watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg);
+	mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name);
+	mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments);
+	watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,200 @@
+// MESSAGE WATCHDOG_PROCESS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 152
+
+typedef struct __mavlink_watchdog_process_status_t 
+{
+	uint16_t watchdog_id; ///< Watchdog ID
+	uint16_t process_id; ///< Process ID
+	uint8_t state; ///< Is running / finished / suspended / crashed
+	uint8_t muted; ///< Is muted
+	int32_t pid; ///< PID
+	uint16_t crashes; ///< Number of crashes
+
+} mavlink_watchdog_process_status_t;
+
+
+
+/**
+ * @brief Pack a watchdog_process_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 watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param state Is running / finished / suspended / crashed
+ * @param muted Is muted
+ * @param pid PID
+ * @param crashes Number of crashes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
+	i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
+	i += put_int32_t_by_index(pid, i, msg->payload); // PID
+	i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a watchdog_process_status message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param state Is running / finished / suspended / crashed
+ * @param muted Is muted
+ * @param pid PID
+ * @param crashes Number of crashes
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
+
+	i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
+	i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
+	i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
+	i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
+	i += put_int32_t_by_index(pid, i, msg->payload); // PID
+	i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a watchdog_process_status struct into a 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 watchdog_process_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
+{
+	return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
+}
+
+/**
+ * @brief Send a watchdog_process_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param watchdog_id Watchdog ID
+ * @param process_id Process ID
+ * @param state Is running / finished / suspended / crashed
+ * @param muted Is muted
+ * @param pid PID
+ * @param crashes Number of crashes
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
+{
+	mavlink_message_t msg;
+	mavlink_msg_watchdog_process_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, state, muted, pid, crashes);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING
+
+/**
+ * @brief Get field watchdog_id from watchdog_process_status message
+ *
+ * @return Watchdog ID
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload)[0];
+	r.b[0] = (msg->payload)[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field process_id from watchdog_process_status message
+ *
+ * @return Process ID
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Get field state from watchdog_process_status message
+ *
+ * @return Is running / finished / suspended / crashed
+ */
+static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
+}
+
+/**
+ * @brief Get field muted from watchdog_process_status message
+ *
+ * @return Is muted
+ */
+static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field pid from watchdog_process_status message
+ *
+ * @return PID
+ */
+static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
+	return (int32_t)r.i;
+}
+
+/**
+ * @brief Get field crashes from watchdog_process_status message
+ *
+ * @return Number of crashes
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a watchdog_process_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param watchdog_process_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status)
+{
+	watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg);
+	watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg);
+	watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg);
+	watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg);
+	watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg);
+	watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/pixhawk/pixhawk.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,81 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://qgroundcontrol.org/mavlink/
+ *	 Generated on Sunday, September 11 2011, 13:52 UTC
+ */
+#ifndef PIXHAWK_H
+#define PIXHAWK_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_PIXHAWK
+
+
+#include "../common/common.h"
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+// ENUM DEFINITIONS
+
+/** @brief  Content Types for data transmission handshake */
+enum DATA_TYPES
+{
+	DATA_TYPE_JPEG_IMAGE=1,
+	DATA_TYPE_RAW_IMAGE=2,
+	DATA_TYPE_KINECT=3,
+	DATA_TYPES_ENUM_END
+};
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_attitude_control.h"
+#include "./mavlink_msg_set_cam_shutter.h"
+#include "./mavlink_msg_image_triggered.h"
+#include "./mavlink_msg_image_trigger_control.h"
+#include "./mavlink_msg_image_available.h"
+#include "./mavlink_msg_vision_position_estimate.h"
+#include "./mavlink_msg_global_vision_position_estimate.h"
+#include "./mavlink_msg_vicon_position_estimate.h"
+#include "./mavlink_msg_vision_speed_estimate.h"
+#include "./mavlink_msg_position_control_setpoint_set.h"
+#include "./mavlink_msg_position_control_offset_set.h"
+#include "./mavlink_msg_position_control_setpoint.h"
+#include "./mavlink_msg_marker.h"
+#include "./mavlink_msg_raw_aux.h"
+#include "./mavlink_msg_aux_status.h"
+#include "./mavlink_msg_watchdog_heartbeat.h"
+#include "./mavlink_msg_watchdog_process_info.h"
+#include "./mavlink_msg_watchdog_process_status.h"
+#include "./mavlink_msg_watchdog_command.h"
+#include "./mavlink_msg_pattern_detected.h"
+#include "./mavlink_msg_point_of_interest.h"
+#include "./mavlink_msg_point_of_interest_connection.h"
+#include "./mavlink_msg_data_transmission_handshake.h"
+#include "./mavlink_msg_encapsulated_data.h"
+#include "./mavlink_msg_brief_feature.h"
+#include "./mavlink_msg_visual_odometry.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 52, 1, 92, 0, 0, 0, 0, 0, 0, 0, 32, 32, 20, 32, 0, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 16, 12, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 18, 0, 0, 0, 0, 0, 106, 42, 54, 0, 0, 0, 0, 0, 0, 0, 8, 255, 53, 0, 0, 0, 0, 0, 0, 0, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/protocol.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,1005 @@
+#ifndef  _MAVLINK_PROTOCOL_H_
+#define  _MAVLINK_PROTOCOL_H_
+
+#include "string.h"
+#include "checksum.h"
+
+#include "mavlink_types.h"
+
+
+/**
+ * @brief Initialize the communication stack
+ *
+ * This function has to be called before using commParseBuffer() to initialize the different status registers.
+ *
+ * @return Will initialize the different buffers and status registers.
+ */
+static void mavlink_parse_state_initialize(mavlink_status_t* initStatus)
+{
+    if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1))
+    {
+        initStatus->ck_a = 0;
+        initStatus->ck_b = 0;
+        initStatus->msg_received = 0;
+        initStatus->buffer_overrun = 0;
+        initStatus->parse_error = 0;
+        initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT;
+        initStatus->packet_idx = 0;
+        initStatus->packet_rx_drop_count = 0;
+        initStatus->packet_rx_success_count = 0;
+        initStatus->current_rx_seq = 0;
+        initStatus->current_tx_seq = 0;
+    }
+}
+
+static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
+{
+    static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+    return &m_mavlink_status[chan];
+}
+
+/**
+ * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
+ *
+ * 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. 
+ *
+ * @warning This function implicitely assumes the message is sent over channel zero.
+ *          if the message is sent over a different channel it will reach the receiver
+ *          without error, BUT the sequence number might be wrong due to the wrong
+ *          channel sequence counter. This will result is wrongly reported excessive
+ *          packet loss. Please use @see mavlink_{pack|encode}_headerless and then
+ *          @see mavlink_finalize_message_chan before sending for a correct channel
+ *          assignment. Please note that the mavlink_msg_xxx_pack and encode functions
+ *          assign channel zero as default and thus induce possible loss counter errors.\
+ *          They have been left to ensure code compatibility.
+ *
+ * @see mavlink_finalize_message_chan
+ * @param msg Message to finalize
+ * @param system_id Id of the sending (this) system, 1-127
+ * @param length Message length, usually just the counter incremented while packing the message
+ */
+ 
+ 
+static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length)
+{
+    // This code part is the same for all messages;
+    uint16_t checksum;
+    msg->len = length;
+    msg->sysid = system_id;
+    msg->compid = component_id;
+    // One sequence number per component
+    msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq;
+    mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1;
+    checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
+    crc_accumulate(50, &checksum);
+    
+    msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
+    msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
+
+    return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES;
+}
+
+/**
+ * @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, usually just the counter incremented while packing the message
+ */
+static inline uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint16_t length)
+{
+    // This code part is the same for all messages;
+    uint16_t checksum;
+    msg->len = length;
+    msg->sysid = system_id;
+    msg->compid = component_id;
+    // One sequence number per component
+    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;
+    checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
+    msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
+    msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
+
+    return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES;
+}
+
+/**
+ * @brief Pack a message to send it over a serial byte stream
+ */
+static inline uint16_t mavlink_msg_to_send_buffer(uint8_t* buffer, const mavlink_message_t* msg)
+{
+    *(buffer+0) = MAVLINK_STX; ///< Start transmit
+    memcpy((buffer+1), msg, msg->len + MAVLINK_CORE_HEADER_LEN); ///< Core header plus payload
+    *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 1) = msg->ck_a;
+    *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 2) = msg->ck_b;
+    return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+    //return 0;
+}
+
+/**
+ * @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;
+}
+
+union checksum_ {
+    uint16_t s;
+    uint8_t c[2];
+};
+
+union __mavlink_bitfield {
+    uint8_t uint8;
+    int8_t int8;
+    uint16_t uint16;
+    int16_t int16;
+    uint32_t uint32;
+    int32_t int32;
+};
+
+
+static inline void mavlink_start_checksum(mavlink_message_t* msg)
+{
+    union checksum_ ck;
+    crc_init(&(ck.s));
+    msg->ck_a = ck.c[0];
+    msg->ck_b = ck.c[1];
+}
+
+static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
+{
+    union checksum_ ck;
+    ck.c[0] = msg->ck_a;
+    ck.c[1] = msg->ck_b;
+    crc_accumulate(c, &(ck.s));
+    msg->ck_a = ck.c[0];
+    msg->ck_b = ck.c[1];
+}
+
+/**
+ * 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. Checksum and other failures will be silently
+ * ignored.
+ *
+ * @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 barse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @return 0 if no message could be decoded, 1 else
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <inttypes.h> // For fixed-width uint8_t type
+ *
+ * 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
+ */
+static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
+{
+    static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
+
+    // Initializes only once, values keep unchanged after first initialization
+    mavlink_parse_state_initialize(mavlink_get_channel_status(chan));
+
+    mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
+    mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
+    int bufferIndex = 0;
+
+    status->msg_received = 0;
+
+    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;
+            mavlink_start_checksum(rxmsg);
+        }
+        break;
+
+    case MAVLINK_PARSE_STATE_GOT_STX:
+        if (status->msg_received)
+        {
+            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:
+        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:
+        rxmsg->payload[status->packet_idx++] = 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 (c != rxmsg->ck_a)
+        {
+            // Check first checksum byte
+            status->parse_error++;
+            status->msg_received = 0;
+            status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+            if (c == MAVLINK_STX)
+            {
+                status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+                mavlink_start_checksum(rxmsg);
+            }
+        }
+        else
+        {
+            status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
+        }*/
+        status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
+        break;
+
+    case MAVLINK_PARSE_STATE_GOT_CRC1:
+        /*if (c != rxmsg->ck_b)
+        {// Check second checksum byte
+            status->parse_error++;
+            status->msg_received = 0;
+            status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+            if (c == MAVLINK_STX)
+            {
+                status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+                mavlink_start_checksum(rxmsg);
+            }
+        }
+        else
+        {
+            // Successfully got message
+            status->msg_received = 1;
+            status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+            memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
+        }*/
+        status->msg_received = 1;
+        status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+        memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
+        break;
+    }
+
+    bufferIndex++;
+    // If a message has been sucessfully decoded, check index
+    if (status->msg_received == 1)
+    {
+        //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_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;
+    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. Checksum and other failures will be silently
+ * ignored.
+ *
+ * @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 barse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @return 0 if no message could be decoded, 1 else
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <inttypes.h> // For fixed-width uint8_t type
+ *
+ * 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
+ */
+
+#define MAVLINK_PACKET_START_CANDIDATES 50
+/*
+static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
+{
+        static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+        static uint8_t m_msgbuf[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_MAX_PACKET_LEN * 2];
+        static uint8_t m_msgbuf_index[MAVLINK_COMM_NUM_BUFFERS];
+        static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
+        static uint8_t m_packet_start[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_PACKET_START_CANDIDATES];
+        static uint8_t m_packet_start_index_read[MAVLINK_COMM_NUM_BUFFERS];
+        static uint8_t m_packet_start_index_write[MAVLINK_COMM_NUM_BUFFERS];
+
+        // Set a packet start candidate index if sign is start sign
+        if (c == MAVLINK_STX)
+        {
+            m_packet_start[chan][++(m_packet_start_index_write[chan]) % MAVLINK_PACKET_START_CANDIDATES] = m_msgbuf_index[chan];
+        }
+
+        // Parse normally, if a CRC mismatch occurs retry with the next packet index
+}
+//    static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+//    static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
+//// Initializes only once, values keep unchanged after first initialization
+//    mavlink_parse_state_initialize(&m_mavlink_status[chan]);
+//
+//mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
+//mavlink_status_t* status = &m_mavlink_status[chan]; ///< The current decode status
+//int bufferIndex = 0;
+//
+//status->msg_received = 0;
+//
+//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;
+//        mavlink_start_checksum(rxmsg);
+//    }
+//    break;
+//
+//case MAVLINK_PARSE_STATE_GOT_STX:
+//    if (status->msg_received)
+//    {
+//        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:
+//    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:
+//    rxmsg->payload[status->packet_idx++] = 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 (c != rxmsg->ck_a)
+//    {
+//        // Check first checksum byte
+//        status->parse_error++;
+//        status->msg_received = 0;
+//        status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+//    }
+//    else
+//    {
+//        status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
+//    }
+//    break;
+//
+//case MAVLINK_PARSE_STATE_GOT_CRC1:
+//    if (c != rxmsg->ck_b)
+//    {// Check second checksum byte
+//        status->parse_error++;
+//        status->msg_received = 0;
+//        status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+//    }
+//    else
+//    {
+//        // Successfully got message
+//        status->msg_received = 1;
+//        status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+//        memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
+//    }
+//    break;
+//}
+
+bufferIndex++;
+// If a message has been sucessfully decoded, check index
+if (status->msg_received == 1)
+{
+    //while(status->current_seq != rxmsg->seq)
+    //{
+    //    status->packet_rx_drop_count++;
+    //               status->current_seq++;
+    //}
+    status->current_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_mavlink_status->current_seq = status->current_seq+1;
+r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
+r_mavlink_status->packet_rx_drop_count = status->parse_error;
+return status->msg_received;
+}
+ */
+
+
+typedef union __generic_16bit
+{
+    uint8_t b[2];
+    int16_t s;
+} generic_16bit;
+
+typedef union __generic_32bit
+{
+    uint8_t b[4];
+    float f;
+    int32_t i;
+    int16_t s;
+} generic_32bit;
+
+typedef union __generic_64bit
+{
+    uint8_t b[8];
+    int64_t ll; ///< Long long (64 bit)
+    double  d;  ///< IEEE-754 double precision floating point
+} generic_64bit;
+
+/**
+ * @brief Place an unsigned byte into the buffer
+ *
+ * @param b the byte to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_uint8_t_by_index(uint8_t b, uint8_t bindex, uint8_t* buffer)
+{
+    *(buffer + bindex) = b;
+    return sizeof(b);
+}
+
+/**
+ * @brief Place a signed byte into the buffer
+ *
+ * @param b the byte to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_int8_t_by_index(int8_t b, int8_t bindex, uint8_t* buffer)
+{
+    *(buffer + bindex) = (uint8_t)b;
+    return sizeof(b);
+}
+
+/**
+ * @brief Place two unsigned bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_uint16_t_by_index(uint16_t b, const uint8_t bindex, uint8_t* buffer)
+{
+    buffer[bindex]   = (b>>8)&0xff;
+    buffer[bindex+1] = (b & 0xff);
+    return sizeof(b);
+}
+
+/**
+ * @brief Place two signed bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_int16_t_by_index(int16_t b, uint8_t bindex, uint8_t* buffer)
+{
+    return put_uint16_t_by_index(b, bindex, buffer);
+}
+
+/**
+ * @brief Place four unsigned bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_uint32_t_by_index(uint32_t b, const uint8_t bindex, uint8_t* buffer)
+{
+    buffer[bindex]   = (b>>24)&0xff;
+    buffer[bindex+1] = (b>>16)&0xff;
+    buffer[bindex+2] = (b>>8)&0xff;
+    buffer[bindex+3] = (b & 0xff);
+    return sizeof(b);
+}
+
+/**
+ * @brief Place four signed bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_int32_t_by_index(int32_t b, uint8_t bindex, uint8_t* buffer)
+{
+    buffer[bindex]   = (b>>24)&0xff;
+    buffer[bindex+1] = (b>>16)&0xff;
+    buffer[bindex+2] = (b>>8)&0xff;
+    buffer[bindex+3] = (b & 0xff);
+    return sizeof(b);
+}
+
+/**
+ * @brief Place four unsigned bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_uint64_t_by_index(uint64_t b, const uint8_t bindex, uint8_t* buffer)
+{
+    buffer[bindex]   = (b>>56)&0xff;
+    buffer[bindex+1] = (b>>48)&0xff;
+    buffer[bindex+2] = (b>>40)&0xff;
+    buffer[bindex+3] = (b>>32)&0xff;
+    buffer[bindex+4] = (b>>24)&0xff;
+    buffer[bindex+5] = (b>>16)&0xff;
+    buffer[bindex+6] = (b>>8)&0xff;
+    buffer[bindex+7] = (b & 0xff);
+    return sizeof(b);
+}
+
+/**
+ * @brief Place four signed bytes into the buffer
+ *
+ * @param b the bytes to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_int64_t_by_index(int64_t b, uint8_t bindex, uint8_t* buffer)
+{
+    return put_uint64_t_by_index(b, bindex, buffer);
+}
+
+/**
+ * @brief Place a float into the buffer
+ *
+ * @param b the float to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_float_by_index(float b, uint8_t bindex, uint8_t* buffer)
+{
+    generic_32bit g;
+    g.f = b;
+    return put_int32_t_by_index(g.i, bindex, buffer);
+}
+
+/**
+ * @brief Place a double into the buffer
+ *
+ * @param b the double to add
+ * @param bindex the position in the packet
+ * @param buffer the packet buffer
+ * @return the new position of the last used byte in the buffer
+ */
+static inline uint8_t put_double_by_index(double b, uint8_t bindex, uint8_t* buffer)
+{
+    generic_64bit g;
+    g.d = b;
+    return put_int64_t_by_index(g.ll, bindex, buffer);
+}
+
+/**
+ * @brief Place an array into the buffer
+ *
+ * @param b the array to add
+ * @param length size of the array (for strings: length WITH '\0' char)
+ * @param bindex the position in the packet
+ * @param buffer packet buffer
+ * @return new position of the last used byte in the buffer
+ */
+static inline uint8_t put_array_by_index(const int8_t* b, uint8_t length, uint8_t bindex, uint8_t* buffer)
+{
+    memcpy(buffer+bindex, b, length);
+    return length;
+}
+
+/**
+ * @brief Place a string into the buffer
+ *
+ * @param b the string to add
+ * @param maxlength size of the array (for strings: length WITHOUT '\0' char)
+ * @param bindex the position in the packet
+ * @param buffer packet buffer
+ * @return new position of the last used byte in the buffer
+ */
+static inline uint8_t put_string_by_index(const char* b, uint8_t maxlength, uint8_t bindex, uint8_t* buffer)
+{
+    uint16_t length = 0;
+    // Copy string into buffer, ensuring not to exceed the buffer size
+    int i;
+    for (i = 1; i < maxlength; i++)
+    {
+        length++;
+        // String characters
+        if (i < (maxlength - 1))
+        {
+            buffer[bindex+i] = b[i];
+            // Stop at null character
+            if (b[i] == '\0')
+            {
+                break;
+            }
+        }
+        // Enforce null termination at end of buffer
+        else if (i == (maxlength - 1))
+        {
+            buffer[i] = '\0';
+        }
+    }
+    // Write length into first field
+    put_uint8_t_by_index(length, bindex, buffer);
+    return length;
+}
+
+/**
+ * @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
+ */
+static inline 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
+    generic_32bit bin;
+    generic_32bit bout;
+    uint8_t i_bit_index, i_byte_index, curr_bits_n;
+    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];
+
+    // 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 <= (8 - i_bit_index))
+        {
+            // Enough space
+            curr_bits_n = 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) & bout.i);
+        
+        // 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 a similar function
+
+/*
+
+#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);
+    }
+}
+ */
+
+static inline void mavlink_send_uart_uint8_t(mavlink_channel_t chan, uint8_t b, uint16_t* checksum)
+{
+    crc_accumulate(b, checksum);
+    comm_send_ch(chan, b);
+}
+
+static inline void mavlink_send_uart_int8_t(mavlink_channel_t chan, int8_t b, uint16_t* checksum)
+{
+    crc_accumulate(b, checksum);
+    comm_send_ch(chan, b);
+}
+
+static inline void mavlink_send_uart_uint16_t(mavlink_channel_t chan, uint16_t b, uint16_t* checksum)
+{
+    char s;
+    s = (b>>8)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b & 0xff);
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+}
+
+static inline void mavlink_send_uart_int16_t(mavlink_channel_t chan, int16_t b, uint16_t* checksum)
+{
+    mavlink_send_uart_uint16_t(chan, b, checksum);
+}
+
+static inline void mavlink_send_uart_uint32_t(mavlink_channel_t chan, uint32_t b, uint16_t* checksum)
+{
+    char s;
+    s = (b>>24)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>16)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>8)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b & 0xff);
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+}
+
+static inline void mavlink_send_uart_int32_t(mavlink_channel_t chan, int32_t b, uint16_t* checksum)
+{
+    mavlink_send_uart_uint32_t(chan, b, checksum);
+}
+
+static inline void mavlink_send_uart_uint64_t(mavlink_channel_t chan, uint64_t b, uint16_t* checksum)
+{
+    char s;
+    s = (b>>56)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>48)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>40)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>32)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>24)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>16)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b>>8)&0xff;
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+    s = (b & 0xff);
+    comm_send_ch(chan, s);
+    crc_accumulate(s, checksum);
+}
+
+static inline void mavlink_send_uart_int64_t(mavlink_channel_t chan, int64_t b, uint16_t* checksum)
+{
+    mavlink_send_uart_uint64_t(chan, b, checksum);
+}
+
+static inline void mavlink_send_uart_float(mavlink_channel_t chan, float b, uint16_t* checksum)
+{
+    generic_32bit g;
+    g.f = b;
+    mavlink_send_uart_uint32_t(chan, g.i, checksum);
+}
+
+static inline void mavlink_send_uart_double(mavlink_channel_t chan, double b, uint16_t* checksum)
+{
+    generic_64bit g;
+    g.d = b;
+    mavlink_send_uart_uint32_t(chan, g.ll, checksum);
+}
+
+static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg)
+{
+    // ARM7 MCU board implementation
+    // Create pointer on message struct
+    // Send STX
+    comm_send_ch(chan, MAVLINK_STX);
+    comm_send_ch(chan, msg->len);
+    comm_send_ch(chan, msg->seq);
+    comm_send_ch(chan, msg->sysid);
+    comm_send_ch(chan, msg->compid);
+    comm_send_ch(chan, msg->msgid);
+    for(uint16_t i = 0; i < msg->len; i++)
+    {
+        comm_send_ch(chan, msg->payload[i]);
+    }
+    comm_send_ch(chan, msg->ck_a);
+    comm_send_ch(chan, msg->ck_b);
+}
+#endif
+
+#endif /* _MAVLINK_PROTOCOL_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "slugs.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_air_data.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,148 @@
+// MESSAGE AIR_DATA PACKING
+
+#define MAVLINK_MSG_ID_AIR_DATA 171
+
+typedef struct __mavlink_air_data_t 
+{
+	float dynamicPressure; ///< Dynamic pressure (Pa)
+	float staticPressure; ///< Static pressure (Pa)
+	uint16_t temperature; ///< Board temperature
+
+} mavlink_air_data_t;
+
+
+
+/**
+ * @brief Pack a air_data 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 dynamicPressure Dynamic pressure (Pa)
+ * @param staticPressure Static pressure (Pa)
+ * @param temperature Board temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
+
+	i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
+	i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
+	i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a air_data message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param dynamicPressure Dynamic pressure (Pa)
+ * @param staticPressure Static pressure (Pa)
+ * @param temperature Board temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
+
+	i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
+	i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
+	i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a air_data struct into a 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 air_data C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
+{
+	return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
+}
+
+/**
+ * @brief Send a air_data message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param dynamicPressure Dynamic pressure (Pa)
+ * @param staticPressure Static pressure (Pa)
+ * @param temperature Board temperature
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature)
+{
+	mavlink_message_t msg;
+	mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, dynamicPressure, staticPressure, temperature);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE AIR_DATA UNPACKING
+
+/**
+ * @brief Get field dynamicPressure from air_data message
+ *
+ * @return Dynamic pressure (Pa)
+ */
+static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field staticPressure from air_data message
+ *
+ * @return Static pressure (Pa)
+ */
+static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field temperature from air_data message
+ *
+ * @return Board temperature
+ */
+static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a air_data message into a struct
+ *
+ * @param msg The message to decode
+ * @param air_data C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data)
+{
+	air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg);
+	air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg);
+	air_data->temperature = mavlink_msg_air_data_get_temperature(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_cpu_load.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,138 @@
+// MESSAGE CPU_LOAD PACKING
+
+#define MAVLINK_MSG_ID_CPU_LOAD 170
+
+typedef struct __mavlink_cpu_load_t 
+{
+	uint8_t sensLoad; ///< Sensor DSC Load
+	uint8_t ctrlLoad; ///< Control DSC Load
+	uint16_t batVolt; ///< Battery Voltage in millivolts
+
+} mavlink_cpu_load_t;
+
+
+
+/**
+ * @brief Pack a cpu_load 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 sensLoad Sensor DSC Load
+ * @param ctrlLoad Control DSC Load
+ * @param batVolt Battery Voltage in millivolts
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
+
+	i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load
+	i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load
+	i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a cpu_load message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param sensLoad Sensor DSC Load
+ * @param ctrlLoad Control DSC Load
+ * @param batVolt Battery Voltage in millivolts
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
+
+	i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load
+	i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load
+	i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a cpu_load struct into a 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 cpu_load C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load)
+{
+	return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt);
+}
+
+/**
+ * @brief Send a cpu_load message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param sensLoad Sensor DSC Load
+ * @param ctrlLoad Control DSC Load
+ * @param batVolt Battery Voltage in millivolts
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
+{
+	mavlink_message_t msg;
+	mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, sensLoad, ctrlLoad, batVolt);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE CPU_LOAD UNPACKING
+
+/**
+ * @brief Get field sensLoad from cpu_load message
+ *
+ * @return Sensor DSC Load
+ */
+static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field ctrlLoad from cpu_load message
+ *
+ * @return Control DSC Load
+ */
+static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field batVolt from cpu_load message
+ *
+ * @return Battery Voltage in millivolts
+ */
+static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a cpu_load message into a struct
+ *
+ * @param msg The message to decode
+ * @param cpu_load C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load)
+{
+	cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg);
+	cpu_load->ctrlLoad = mavlink_msg_cpu_load_get_ctrlLoad(msg);
+	cpu_load->batVolt = mavlink_msg_cpu_load_get_batVolt(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,121 @@
+// MESSAGE CTRL_SRFC_PT PACKING
+
+#define MAVLINK_MSG_ID_CTRL_SRFC_PT 181
+
+typedef struct __mavlink_ctrl_srfc_pt_t 
+{
+	uint8_t target; ///< The system setting the commands
+	uint16_t bitfieldPt; ///< Bitfield containing the PT configuration
+
+} mavlink_ctrl_srfc_pt_t;
+
+
+
+/**
+ * @brief Pack a ctrl_srfc_pt 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 target The system setting the commands
+ * @param bitfieldPt Bitfield containing the PT configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t bitfieldPt)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
+	i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a ctrl_srfc_pt message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system setting the commands
+ * @param bitfieldPt Bitfield containing the PT configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t bitfieldPt)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
+	i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a ctrl_srfc_pt struct into a 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 ctrl_srfc_pt C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ctrl_srfc_pt_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
+{
+	return mavlink_msg_ctrl_srfc_pt_pack(system_id, component_id, msg, ctrl_srfc_pt->target, ctrl_srfc_pt->bitfieldPt);
+}
+
+/**
+ * @brief Send a ctrl_srfc_pt message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system setting the commands
+ * @param bitfieldPt Bitfield containing the PT configuration
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ctrl_srfc_pt_send(mavlink_channel_t chan, uint8_t target, uint16_t bitfieldPt)
+{
+	mavlink_message_t msg;
+	mavlink_msg_ctrl_srfc_pt_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, bitfieldPt);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE CTRL_SRFC_PT UNPACKING
+
+/**
+ * @brief Get field target from ctrl_srfc_pt message
+ *
+ * @return The system setting the commands
+ */
+static inline uint8_t mavlink_msg_ctrl_srfc_pt_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field bitfieldPt from ctrl_srfc_pt message
+ *
+ * @return Bitfield containing the PT configuration
+ */
+static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a ctrl_srfc_pt message into a struct
+ *
+ * @param msg The message to decode
+ * @param ctrl_srfc_pt C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ctrl_srfc_pt_decode(const mavlink_message_t* msg, mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
+{
+	ctrl_srfc_pt->target = mavlink_msg_ctrl_srfc_pt_get_target(msg);
+	ctrl_srfc_pt->bitfieldPt = mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_data_log.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,216 @@
+// MESSAGE DATA_LOG PACKING
+
+#define MAVLINK_MSG_ID_DATA_LOG 177
+
+typedef struct __mavlink_data_log_t 
+{
+	float fl_1; ///< Log value 1 
+	float fl_2; ///< Log value 2 
+	float fl_3; ///< Log value 3 
+	float fl_4; ///< Log value 4 
+	float fl_5; ///< Log value 5 
+	float fl_6; ///< Log value 6 
+
+} mavlink_data_log_t;
+
+
+
+/**
+ * @brief Pack a data_log 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 fl_1 Log value 1 
+ * @param fl_2 Log value 2 
+ * @param fl_3 Log value 3 
+ * @param fl_4 Log value 4 
+ * @param fl_5 Log value 5 
+ * @param fl_6 Log value 6 
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
+
+	i += put_float_by_index(fl_1, i, msg->payload); // Log value 1 
+	i += put_float_by_index(fl_2, i, msg->payload); // Log value 2 
+	i += put_float_by_index(fl_3, i, msg->payload); // Log value 3 
+	i += put_float_by_index(fl_4, i, msg->payload); // Log value 4 
+	i += put_float_by_index(fl_5, i, msg->payload); // Log value 5 
+	i += put_float_by_index(fl_6, i, msg->payload); // Log value 6 
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a data_log message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param fl_1 Log value 1 
+ * @param fl_2 Log value 2 
+ * @param fl_3 Log value 3 
+ * @param fl_4 Log value 4 
+ * @param fl_5 Log value 5 
+ * @param fl_6 Log value 6 
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
+
+	i += put_float_by_index(fl_1, i, msg->payload); // Log value 1 
+	i += put_float_by_index(fl_2, i, msg->payload); // Log value 2 
+	i += put_float_by_index(fl_3, i, msg->payload); // Log value 3 
+	i += put_float_by_index(fl_4, i, msg->payload); // Log value 4 
+	i += put_float_by_index(fl_5, i, msg->payload); // Log value 5 
+	i += put_float_by_index(fl_6, i, msg->payload); // Log value 6 
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a data_log struct into a 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 data_log C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log)
+{
+	return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6);
+}
+
+/**
+ * @brief Send a data_log message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param fl_1 Log value 1 
+ * @param fl_2 Log value 2 
+ * @param fl_3 Log value 3 
+ * @param fl_4 Log value 4 
+ * @param fl_5 Log value 5 
+ * @param fl_6 Log value 6 
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
+{
+	mavlink_message_t msg;
+	mavlink_msg_data_log_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE DATA_LOG UNPACKING
+
+/**
+ * @brief Get field fl_1 from data_log message
+ *
+ * @return Log value 1 
+ */
+static inline float mavlink_msg_data_log_get_fl_1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fl_2 from data_log message
+ *
+ * @return Log value 2 
+ */
+static inline float mavlink_msg_data_log_get_fl_2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fl_3 from data_log message
+ *
+ * @return Log value 3 
+ */
+static inline float mavlink_msg_data_log_get_fl_3(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fl_4 from data_log message
+ *
+ * @return Log value 4 
+ */
+static inline float mavlink_msg_data_log_get_fl_4(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fl_5 from data_log message
+ *
+ * @return Log value 5 
+ */
+static inline float mavlink_msg_data_log_get_fl_5(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fl_6 from data_log message
+ *
+ * @return Log value 6 
+ */
+static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a data_log message into a struct
+ *
+ * @param msg The message to decode
+ * @param data_log C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log)
+{
+	data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg);
+	data_log->fl_2 = mavlink_msg_data_log_get_fl_2(msg);
+	data_log->fl_3 = mavlink_msg_data_log_get_fl_3(msg);
+	data_log->fl_4 = mavlink_msg_data_log_get_fl_4(msg);
+	data_log->fl_5 = mavlink_msg_data_log_get_fl_5(msg);
+	data_log->fl_6 = mavlink_msg_data_log_get_fl_6(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_diagnostic.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,210 @@
+// MESSAGE DIAGNOSTIC PACKING
+
+#define MAVLINK_MSG_ID_DIAGNOSTIC 173
+
+typedef struct __mavlink_diagnostic_t 
+{
+	float diagFl1; ///< Diagnostic float 1
+	float diagFl2; ///< Diagnostic float 2
+	float diagFl3; ///< Diagnostic float 3
+	int16_t diagSh1; ///< Diagnostic short 1
+	int16_t diagSh2; ///< Diagnostic short 2
+	int16_t diagSh3; ///< Diagnostic short 3
+
+} mavlink_diagnostic_t;
+
+
+
+/**
+ * @brief Pack a diagnostic 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 diagFl1 Diagnostic float 1
+ * @param diagFl2 Diagnostic float 2
+ * @param diagFl3 Diagnostic float 3
+ * @param diagSh1 Diagnostic short 1
+ * @param diagSh2 Diagnostic short 2
+ * @param diagSh3 Diagnostic short 3
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
+
+	i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1
+	i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2
+	i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3
+	i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1
+	i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2
+	i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a diagnostic message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param diagFl1 Diagnostic float 1
+ * @param diagFl2 Diagnostic float 2
+ * @param diagFl3 Diagnostic float 3
+ * @param diagSh1 Diagnostic short 1
+ * @param diagSh2 Diagnostic short 2
+ * @param diagSh3 Diagnostic short 3
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
+
+	i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1
+	i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2
+	i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3
+	i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1
+	i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2
+	i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a diagnostic struct into a 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 diagnostic C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic)
+{
+	return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
+}
+
+/**
+ * @brief Send a diagnostic message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param diagFl1 Diagnostic float 1
+ * @param diagFl2 Diagnostic float 2
+ * @param diagFl3 Diagnostic float 3
+ * @param diagSh1 Diagnostic short 1
+ * @param diagSh2 Diagnostic short 2
+ * @param diagSh3 Diagnostic short 3
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
+{
+	mavlink_message_t msg;
+	mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE DIAGNOSTIC UNPACKING
+
+/**
+ * @brief Get field diagFl1 from diagnostic message
+ *
+ * @return Diagnostic float 1
+ */
+static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field diagFl2 from diagnostic message
+ *
+ * @return Diagnostic float 2
+ */
+static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field diagFl3 from diagnostic message
+ *
+ * @return Diagnostic float 3
+ */
+static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field diagSh1 from diagnostic message
+ *
+ * @return Diagnostic short 1
+ */
+static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field diagSh2 from diagnostic message
+ *
+ * @return Diagnostic short 2
+ */
+static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Get field diagSh3 from diagnostic message
+ *
+ * @return Diagnostic short 3
+ */
+static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1];
+	return (int16_t)r.s;
+}
+
+/**
+ * @brief Decode a diagnostic message into a struct
+ *
+ * @param msg The message to decode
+ * @param diagnostic C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic)
+{
+	diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg);
+	diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg);
+	diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg);
+	diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg);
+	diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg);
+	diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_gps_date_time.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,203 @@
+// MESSAGE GPS_DATE_TIME PACKING
+
+#define MAVLINK_MSG_ID_GPS_DATE_TIME 179
+
+typedef struct __mavlink_gps_date_time_t 
+{
+	uint8_t year; ///< Year reported by Gps 
+	uint8_t month; ///< Month reported by Gps 
+	uint8_t day; ///< Day reported by Gps 
+	uint8_t hour; ///< Hour reported by Gps 
+	uint8_t min; ///< Min reported by Gps 
+	uint8_t sec; ///< Sec reported by Gps  
+	uint8_t visSat; ///< Visible sattelites reported by Gps  
+
+} mavlink_gps_date_time_t;
+
+
+
+/**
+ * @brief Pack a gps_date_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 year Year reported by Gps 
+ * @param month Month reported by Gps 
+ * @param day Day reported by Gps 
+ * @param hour Hour reported by Gps 
+ * @param min Min reported by Gps 
+ * @param sec Sec reported by Gps  
+ * @param visSat Visible sattelites reported by Gps  
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
+
+	i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps 
+	i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps 
+	i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps 
+	i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps 
+	i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps 
+	i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps  
+	i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps  
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a gps_date_time message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param year Year reported by Gps 
+ * @param month Month reported by Gps 
+ * @param day Day reported by Gps 
+ * @param hour Hour reported by Gps 
+ * @param min Min reported by Gps 
+ * @param sec Sec reported by Gps  
+ * @param visSat Visible sattelites reported by Gps  
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
+
+	i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps 
+	i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps 
+	i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps 
+	i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps 
+	i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps 
+	i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps  
+	i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps  
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a gps_date_time struct into a 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 gps_date_time C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time)
+{
+	return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat);
+}
+
+/**
+ * @brief Send a gps_date_time message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param year Year reported by Gps 
+ * @param month Month reported by Gps 
+ * @param day Day reported by Gps 
+ * @param hour Hour reported by Gps 
+ * @param min Min reported by Gps 
+ * @param sec Sec reported by Gps  
+ * @param visSat Visible sattelites reported by Gps  
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
+{
+	mavlink_message_t msg;
+	mavlink_msg_gps_date_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, year, month, day, hour, min, sec, visSat);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE GPS_DATE_TIME UNPACKING
+
+/**
+ * @brief Get field year from gps_date_time message
+ *
+ * @return Year reported by Gps 
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field month from gps_date_time message
+ *
+ * @return Month reported by Gps 
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field day from gps_date_time message
+ *
+ * @return Day reported by Gps 
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field hour from gps_date_time message
+ *
+ * @return Hour reported by Gps 
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field min from gps_date_time message
+ *
+ * @return Min reported by Gps 
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field sec from gps_date_time message
+ *
+ * @return Sec reported by Gps  
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field visSat from gps_date_time message
+ *
+ * @return Visible sattelites reported by Gps  
+ */
+static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a gps_date_time message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_date_time C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time)
+{
+	gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg);
+	gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg);
+	gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg);
+	gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg);
+	gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg);
+	gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg);
+	gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_mid_lvl_cmds.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,167 @@
+// MESSAGE MID_LVL_CMDS PACKING
+
+#define MAVLINK_MSG_ID_MID_LVL_CMDS 180
+
+typedef struct __mavlink_mid_lvl_cmds_t 
+{
+	uint8_t target; ///< The system setting the commands
+	float hCommand; ///< Commanded Airspeed
+	float uCommand; ///< Log value 2 
+	float rCommand; ///< Log value 3 
+
+} mavlink_mid_lvl_cmds_t;
+
+
+
+/**
+ * @brief Pack a mid_lvl_cmds 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 target The system setting the commands
+ * @param hCommand Commanded Airspeed
+ * @param uCommand Log value 2 
+ * @param rCommand Log value 3 
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
+	i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
+	i += put_float_by_index(uCommand, i, msg->payload); // Log value 2 
+	i += put_float_by_index(rCommand, i, msg->payload); // Log value 3 
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a mid_lvl_cmds message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system setting the commands
+ * @param hCommand Commanded Airspeed
+ * @param uCommand Log value 2 
+ * @param rCommand Log value 3 
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
+	i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
+	i += put_float_by_index(uCommand, i, msg->payload); // Log value 2 
+	i += put_float_by_index(rCommand, i, msg->payload); // Log value 3 
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a mid_lvl_cmds struct into a 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 mid_lvl_cmds C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
+{
+	return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand);
+}
+
+/**
+ * @brief Send a mid_lvl_cmds message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system setting the commands
+ * @param hCommand Commanded Airspeed
+ * @param uCommand Log value 2 
+ * @param rCommand Log value 3 
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand)
+{
+	mavlink_message_t msg;
+	mavlink_msg_mid_lvl_cmds_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, hCommand, uCommand, rCommand);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE MID_LVL_CMDS UNPACKING
+
+/**
+ * @brief Get field target from mid_lvl_cmds message
+ *
+ * @return The system setting the commands
+ */
+static inline uint8_t mavlink_msg_mid_lvl_cmds_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field hCommand from mid_lvl_cmds message
+ *
+ * @return Commanded Airspeed
+ */
+static inline float mavlink_msg_mid_lvl_cmds_get_hCommand(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field uCommand from mid_lvl_cmds message
+ *
+ * @return Log value 2 
+ */
+static inline float mavlink_msg_mid_lvl_cmds_get_uCommand(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field rCommand from mid_lvl_cmds message
+ *
+ * @return Log value 3 
+ */
+static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a mid_lvl_cmds message into a struct
+ *
+ * @param msg The message to decode
+ * @param mid_lvl_cmds C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
+{
+	mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg);
+	mid_lvl_cmds->hCommand = mavlink_msg_mid_lvl_cmds_get_hCommand(msg);
+	mid_lvl_cmds->uCommand = mavlink_msg_mid_lvl_cmds_get_uCommand(msg);
+	mid_lvl_cmds->rCommand = mavlink_msg_mid_lvl_cmds_get_rCommand(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_sensor_bias.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,216 @@
+// MESSAGE SENSOR_BIAS PACKING
+
+#define MAVLINK_MSG_ID_SENSOR_BIAS 172
+
+typedef struct __mavlink_sensor_bias_t 
+{
+	float axBias; ///< Accelerometer X bias (m/s)
+	float ayBias; ///< Accelerometer Y bias (m/s)
+	float azBias; ///< Accelerometer Z bias (m/s)
+	float gxBias; ///< Gyro X bias (rad/s)
+	float gyBias; ///< Gyro Y bias (rad/s)
+	float gzBias; ///< Gyro Z bias (rad/s)
+
+} mavlink_sensor_bias_t;
+
+
+
+/**
+ * @brief Pack a sensor_bias 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 axBias Accelerometer X bias (m/s)
+ * @param ayBias Accelerometer Y bias (m/s)
+ * @param azBias Accelerometer Z bias (m/s)
+ * @param gxBias Gyro X bias (rad/s)
+ * @param gyBias Gyro Y bias (rad/s)
+ * @param gzBias Gyro Z bias (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
+
+	i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s)
+	i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s)
+	i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s)
+	i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s)
+	i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s)
+	i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a sensor_bias message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param axBias Accelerometer X bias (m/s)
+ * @param ayBias Accelerometer Y bias (m/s)
+ * @param azBias Accelerometer Z bias (m/s)
+ * @param gxBias Gyro X bias (rad/s)
+ * @param gyBias Gyro Y bias (rad/s)
+ * @param gzBias Gyro Z bias (rad/s)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
+
+	i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s)
+	i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s)
+	i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s)
+	i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s)
+	i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s)
+	i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a sensor_bias struct into a 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 sensor_bias C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
+{
+	return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
+}
+
+/**
+ * @brief Send a sensor_bias message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param axBias Accelerometer X bias (m/s)
+ * @param ayBias Accelerometer Y bias (m/s)
+ * @param azBias Accelerometer Z bias (m/s)
+ * @param gxBias Gyro X bias (rad/s)
+ * @param gyBias Gyro Y bias (rad/s)
+ * @param gzBias Gyro Z bias (rad/s)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
+{
+	mavlink_message_t msg;
+	mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SENSOR_BIAS UNPACKING
+
+/**
+ * @brief Get field axBias from sensor_bias message
+ *
+ * @return Accelerometer X bias (m/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ayBias from sensor_bias message
+ *
+ * @return Accelerometer Y bias (m/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field azBias from sensor_bias message
+ *
+ * @return Accelerometer Z bias (m/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gxBias from sensor_bias message
+ *
+ * @return Gyro X bias (rad/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyBias from sensor_bias message
+ *
+ * @return Gyro Y bias (rad/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gzBias from sensor_bias message
+ *
+ * @return Gyro Z bias (rad/s)
+ */
+static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a sensor_bias message into a struct
+ *
+ * @param msg The message to decode
+ * @param sensor_bias C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
+{
+	sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
+	sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
+	sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg);
+	sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg);
+	sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg);
+	sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_slugs_action.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,138 @@
+// MESSAGE SLUGS_ACTION PACKING
+
+#define MAVLINK_MSG_ID_SLUGS_ACTION 183
+
+typedef struct __mavlink_slugs_action_t 
+{
+	uint8_t target; ///< The system reporting the action
+	uint8_t actionId; ///< Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+	uint16_t actionVal; ///< Value associated with the action
+
+} mavlink_slugs_action_t;
+
+
+
+/**
+ * @brief Pack a slugs_action 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 target The system reporting the action
+ * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+ * @param actionVal Value associated with the action
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t actionId, uint16_t actionVal)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action
+	i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+	i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a slugs_action message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target The system reporting the action
+ * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+ * @param actionVal Value associated with the action
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_slugs_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t actionId, uint16_t actionVal)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION;
+
+	i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action
+	i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+	i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a slugs_action struct into a 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 slugs_action C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_slugs_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_action_t* slugs_action)
+{
+	return mavlink_msg_slugs_action_pack(system_id, component_id, msg, slugs_action->target, slugs_action->actionId, slugs_action->actionVal);
+}
+
+/**
+ * @brief Send a slugs_action message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target The system reporting the action
+ * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+ * @param actionVal Value associated with the action
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_slugs_action_send(mavlink_channel_t chan, uint8_t target, uint8_t actionId, uint16_t actionVal)
+{
+	mavlink_message_t msg;
+	mavlink_msg_slugs_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, actionId, actionVal);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SLUGS_ACTION UNPACKING
+
+/**
+ * @brief Get field target from slugs_action message
+ *
+ * @return The system reporting the action
+ */
+static inline uint8_t mavlink_msg_slugs_action_get_target(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field actionId from slugs_action message
+ *
+ * @return Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
+ */
+static inline uint8_t mavlink_msg_slugs_action_get_actionId(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field actionVal from slugs_action message
+ *
+ * @return Value associated with the action
+ */
+static inline uint16_t mavlink_msg_slugs_action_get_actionVal(const mavlink_message_t* msg)
+{
+	generic_16bit r;
+	r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+	r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
+	return (uint16_t)r.s;
+}
+
+/**
+ * @brief Decode a slugs_action message into a struct
+ *
+ * @param msg The message to decode
+ * @param slugs_action C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_slugs_action_decode(const mavlink_message_t* msg, mavlink_slugs_action_t* slugs_action)
+{
+	slugs_action->target = mavlink_msg_slugs_action_get_target(msg);
+	slugs_action->actionId = mavlink_msg_slugs_action_get_actionId(msg);
+	slugs_action->actionVal = mavlink_msg_slugs_action_get_actionVal(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/mavlink_msg_slugs_navigation.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,272 @@
+// MESSAGE SLUGS_NAVIGATION PACKING
+
+#define MAVLINK_MSG_ID_SLUGS_NAVIGATION 176
+
+typedef struct __mavlink_slugs_navigation_t 
+{
+	float u_m; ///< Measured Airspeed prior to the Nav Filter
+	float phi_c; ///< Commanded Roll
+	float theta_c; ///< Commanded Pitch
+	float psiDot_c; ///< Commanded Turn rate
+	float ay_body; ///< Y component of the body acceleration
+	float totalDist; ///< Total Distance to Run on this leg of Navigation
+	float dist2Go; ///< Remaining distance to Run on this leg of Navigation
+	uint8_t fromWP; ///< Origin WP
+	uint8_t toWP; ///< Destination WP
+
+} mavlink_slugs_navigation_t;
+
+
+
+/**
+ * @brief Pack a slugs_navigation 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 u_m Measured Airspeed prior to the Nav Filter
+ * @param phi_c Commanded Roll
+ * @param theta_c Commanded Pitch
+ * @param psiDot_c Commanded Turn rate
+ * @param ay_body Y component of the body acceleration
+ * @param totalDist Total Distance to Run on this leg of Navigation
+ * @param dist2Go Remaining distance to Run on this leg of Navigation
+ * @param fromWP Origin WP
+ * @param toWP Destination WP
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION;
+
+	i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter
+	i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll
+	i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch
+	i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate
+	i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration
+	i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation
+	i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation
+	i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP
+	i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a slugs_navigation message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param u_m Measured Airspeed prior to the Nav Filter
+ * @param phi_c Commanded Roll
+ * @param theta_c Commanded Pitch
+ * @param psiDot_c Commanded Turn rate
+ * @param ay_body Y component of the body acceleration
+ * @param totalDist Total Distance to Run on this leg of Navigation
+ * @param dist2Go Remaining distance to Run on this leg of Navigation
+ * @param fromWP Origin WP
+ * @param toWP Destination WP
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION;
+
+	i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter
+	i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll
+	i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch
+	i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate
+	i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration
+	i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation
+	i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation
+	i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP
+	i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a slugs_navigation struct into a 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 slugs_navigation C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_slugs_navigation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_navigation_t* slugs_navigation)
+{
+	return mavlink_msg_slugs_navigation_pack(system_id, component_id, msg, slugs_navigation->u_m, slugs_navigation->phi_c, slugs_navigation->theta_c, slugs_navigation->psiDot_c, slugs_navigation->ay_body, slugs_navigation->totalDist, slugs_navigation->dist2Go, slugs_navigation->fromWP, slugs_navigation->toWP);
+}
+
+/**
+ * @brief Send a slugs_navigation message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param u_m Measured Airspeed prior to the Nav Filter
+ * @param phi_c Commanded Roll
+ * @param theta_c Commanded Pitch
+ * @param psiDot_c Commanded Turn rate
+ * @param ay_body Y component of the body acceleration
+ * @param totalDist Total Distance to Run on this leg of Navigation
+ * @param dist2Go Remaining distance to Run on this leg of Navigation
+ * @param fromWP Origin WP
+ * @param toWP Destination WP
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_slugs_navigation_send(mavlink_channel_t chan, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
+{
+	mavlink_message_t msg;
+	mavlink_msg_slugs_navigation_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE SLUGS_NAVIGATION UNPACKING
+
+/**
+ * @brief Get field u_m from slugs_navigation message
+ *
+ * @return Measured Airspeed prior to the Nav Filter
+ */
+static inline float mavlink_msg_slugs_navigation_get_u_m(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload)[0];
+	r.b[2] = (msg->payload)[1];
+	r.b[1] = (msg->payload)[2];
+	r.b[0] = (msg->payload)[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field phi_c from slugs_navigation message
+ *
+ * @return Commanded Roll
+ */
+static inline float mavlink_msg_slugs_navigation_get_phi_c(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field theta_c from slugs_navigation message
+ *
+ * @return Commanded Pitch
+ */
+static inline float mavlink_msg_slugs_navigation_get_theta_c(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field psiDot_c from slugs_navigation message
+ *
+ * @return Commanded Turn rate
+ */
+static inline float mavlink_msg_slugs_navigation_get_psiDot_c(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field ay_body from slugs_navigation message
+ *
+ * @return Y component of the body acceleration
+ */
+static inline float mavlink_msg_slugs_navigation_get_ay_body(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field totalDist from slugs_navigation message
+ *
+ * @return Total Distance to Run on this leg of Navigation
+ */
+static inline float mavlink_msg_slugs_navigation_get_totalDist(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field dist2Go from slugs_navigation message
+ *
+ * @return Remaining distance to Run on this leg of Navigation
+ */
+static inline float mavlink_msg_slugs_navigation_get_dist2Go(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field fromWP from slugs_navigation message
+ *
+ * @return Origin WP
+ */
+static inline uint8_t mavlink_msg_slugs_navigation_get_fromWP(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+}
+
+/**
+ * @brief Get field toWP from slugs_navigation message
+ *
+ * @return Destination WP
+ */
+static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a slugs_navigation message into a struct
+ *
+ * @param msg The message to decode
+ * @param slugs_navigation C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_slugs_navigation_decode(const mavlink_message_t* msg, mavlink_slugs_navigation_t* slugs_navigation)
+{
+	slugs_navigation->u_m = mavlink_msg_slugs_navigation_get_u_m(msg);
+	slugs_navigation->phi_c = mavlink_msg_slugs_navigation_get_phi_c(msg);
+	slugs_navigation->theta_c = mavlink_msg_slugs_navigation_get_theta_c(msg);
+	slugs_navigation->psiDot_c = mavlink_msg_slugs_navigation_get_psiDot_c(msg);
+	slugs_navigation->ay_body = mavlink_msg_slugs_navigation_get_ay_body(msg);
+	slugs_navigation->totalDist = mavlink_msg_slugs_navigation_get_totalDist(msg);
+	slugs_navigation->dist2Go = mavlink_msg_slugs_navigation_get_dist2Go(msg);
+	slugs_navigation->fromWP = mavlink_msg_slugs_navigation_get_fromWP(msg);
+	slugs_navigation->toWP = mavlink_msg_slugs_navigation_get_toWP(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/slugs/slugs.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,56 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://qgroundcontrol.org/mavlink/
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef SLUGS_H
+#define SLUGS_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_SLUGS
+
+
+#include "../common/common.h"
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+// ENUM DEFINITIONS
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_cpu_load.h"
+#include "./mavlink_msg_air_data.h"
+#include "./mavlink_msg_sensor_bias.h"
+#include "./mavlink_msg_diagnostic.h"
+#include "./mavlink_msg_slugs_navigation.h"
+#include "./mavlink_msg_data_log.h"
+#include "./mavlink_msg_gps_date_time.h"
+#include "./mavlink_msg_mid_lvl_cmds.h"
+#include "./mavlink_msg_ctrl_srfc_pt.h"
+#include "./mavlink_msg_slugs_action.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/mavlink.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,11 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://pixhawk.ethz.ch/software/mavlink
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#include "ualberta.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/mavlink_msg_nav_filter_bias.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,242 @@
+// MESSAGE NAV_FILTER_BIAS PACKING
+
+#define MAVLINK_MSG_ID_NAV_FILTER_BIAS 220
+
+typedef struct __mavlink_nav_filter_bias_t 
+{
+	uint64_t usec; ///< Timestamp (microseconds)
+	float accel_0; ///< b_f[0]
+	float accel_1; ///< b_f[1]
+	float accel_2; ///< b_f[2]
+	float gyro_0; ///< b_f[0]
+	float gyro_1; ///< b_f[1]
+	float gyro_2; ///< b_f[2]
+
+} mavlink_nav_filter_bias_t;
+
+
+
+/**
+ * @brief Pack a nav_filter_bias 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 usec Timestamp (microseconds)
+ * @param accel_0 b_f[0]
+ * @param accel_1 b_f[1]
+ * @param accel_2 b_f[2]
+ * @param gyro_0 b_f[0]
+ * @param gyro_1 b_f[1]
+ * @param gyro_2 b_f[2]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nav_filter_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
+	i += put_float_by_index(accel_0, i, msg->payload); // b_f[0]
+	i += put_float_by_index(accel_1, i, msg->payload); // b_f[1]
+	i += put_float_by_index(accel_2, i, msg->payload); // b_f[2]
+	i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0]
+	i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1]
+	i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2]
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a nav_filter_bias message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param usec Timestamp (microseconds)
+ * @param accel_0 b_f[0]
+ * @param accel_1 b_f[1]
+ * @param accel_2 b_f[2]
+ * @param gyro_0 b_f[0]
+ * @param gyro_1 b_f[1]
+ * @param gyro_2 b_f[2]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS;
+
+	i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
+	i += put_float_by_index(accel_0, i, msg->payload); // b_f[0]
+	i += put_float_by_index(accel_1, i, msg->payload); // b_f[1]
+	i += put_float_by_index(accel_2, i, msg->payload); // b_f[2]
+	i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0]
+	i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1]
+	i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2]
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a nav_filter_bias struct into a 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 nav_filter_bias C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_nav_filter_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_filter_bias_t* nav_filter_bias)
+{
+	return mavlink_msg_nav_filter_bias_pack(system_id, component_id, msg, nav_filter_bias->usec, nav_filter_bias->accel_0, nav_filter_bias->accel_1, nav_filter_bias->accel_2, nav_filter_bias->gyro_0, nav_filter_bias->gyro_1, nav_filter_bias->gyro_2);
+}
+
+/**
+ * @brief Send a nav_filter_bias message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param usec Timestamp (microseconds)
+ * @param accel_0 b_f[0]
+ * @param accel_1 b_f[1]
+ * @param accel_2 b_f[2]
+ * @param gyro_0 b_f[0]
+ * @param gyro_1 b_f[1]
+ * @param gyro_2 b_f[2]
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_nav_filter_bias_send(mavlink_channel_t chan, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2)
+{
+	mavlink_message_t msg;
+	mavlink_msg_nav_filter_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE NAV_FILTER_BIAS UNPACKING
+
+/**
+ * @brief Get field usec from nav_filter_bias message
+ *
+ * @return Timestamp (microseconds)
+ */
+static inline uint64_t mavlink_msg_nav_filter_bias_get_usec(const mavlink_message_t* msg)
+{
+	generic_64bit r;
+	r.b[7] = (msg->payload)[0];
+	r.b[6] = (msg->payload)[1];
+	r.b[5] = (msg->payload)[2];
+	r.b[4] = (msg->payload)[3];
+	r.b[3] = (msg->payload)[4];
+	r.b[2] = (msg->payload)[5];
+	r.b[1] = (msg->payload)[6];
+	r.b[0] = (msg->payload)[7];
+	return (uint64_t)r.ll;
+}
+
+/**
+ * @brief Get field accel_0 from nav_filter_bias message
+ *
+ * @return b_f[0]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_accel_0(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field accel_1 from nav_filter_bias message
+ *
+ * @return b_f[1]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_accel_1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field accel_2 from nav_filter_bias message
+ *
+ * @return b_f[2]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_accel_2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyro_0 from nav_filter_bias message
+ *
+ * @return b_f[0]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_gyro_0(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyro_1 from nav_filter_bias message
+ *
+ * @return b_f[1]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_gyro_1(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Get field gyro_2 from nav_filter_bias message
+ *
+ * @return b_f[2]
+ */
+static inline float mavlink_msg_nav_filter_bias_get_gyro_2(const mavlink_message_t* msg)
+{
+	generic_32bit r;
+	r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
+	r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
+	r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
+	r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
+	return (float)r.f;
+}
+
+/**
+ * @brief Decode a nav_filter_bias message into a struct
+ *
+ * @param msg The message to decode
+ * @param nav_filter_bias C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_nav_filter_bias_decode(const mavlink_message_t* msg, mavlink_nav_filter_bias_t* nav_filter_bias)
+{
+	nav_filter_bias->usec = mavlink_msg_nav_filter_bias_get_usec(msg);
+	nav_filter_bias->accel_0 = mavlink_msg_nav_filter_bias_get_accel_0(msg);
+	nav_filter_bias->accel_1 = mavlink_msg_nav_filter_bias_get_accel_1(msg);
+	nav_filter_bias->accel_2 = mavlink_msg_nav_filter_bias_get_accel_2(msg);
+	nav_filter_bias->gyro_0 = mavlink_msg_nav_filter_bias_get_gyro_0(msg);
+	nav_filter_bias->gyro_1 = mavlink_msg_nav_filter_bias_get_gyro_1(msg);
+	nav_filter_bias->gyro_2 = mavlink_msg_nav_filter_bias_get_gyro_2(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/mavlink_msg_radio_calibration.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,204 @@
+// MESSAGE RADIO_CALIBRATION PACKING
+
+#define MAVLINK_MSG_ID_RADIO_CALIBRATION 221
+
+typedef struct __mavlink_radio_calibration_t 
+{
+	uint16_t aileron[3]; ///< Aileron setpoints: left, center, right
+	uint16_t elevator[3]; ///< Elevator setpoints: nose down, center, nose up
+	uint16_t rudder[3]; ///< Rudder setpoints: nose left, center, nose right
+	uint16_t gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode
+	uint16_t pitch[5]; ///< Pitch curve setpoints (every 25%)
+	uint16_t throttle[5]; ///< Throttle curve setpoints (every 25%)
+
+} mavlink_radio_calibration_t;
+
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN 3
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN 3
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN 3
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN 2
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN 5
+#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN 5
+
+
+/**
+ * @brief Pack a radio_calibration 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 aileron Aileron setpoints: left, center, right
+ * @param elevator Elevator setpoints: nose down, center, nose up
+ * @param rudder Rudder setpoints: nose left, center, nose right
+ * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode
+ * @param pitch Pitch curve setpoints (every 25%)
+ * @param throttle Throttle curve setpoints (every 25%)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION;
+
+	i += put_array_by_index((const int8_t*)aileron, sizeof(uint16_t)*3, i, msg->payload); // Aileron setpoints: left, center, right
+	i += put_array_by_index((const int8_t*)elevator, sizeof(uint16_t)*3, i, msg->payload); // Elevator setpoints: nose down, center, nose up
+	i += put_array_by_index((const int8_t*)rudder, sizeof(uint16_t)*3, i, msg->payload); // Rudder setpoints: nose left, center, nose right
+	i += put_array_by_index((const int8_t*)gyro, sizeof(uint16_t)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode
+	i += put_array_by_index((const int8_t*)pitch, sizeof(uint16_t)*5, i, msg->payload); // Pitch curve setpoints (every 25%)
+	i += put_array_by_index((const int8_t*)throttle, sizeof(uint16_t)*5, i, msg->payload); // Throttle curve setpoints (every 25%)
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a radio_calibration message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param aileron Aileron setpoints: left, center, right
+ * @param elevator Elevator setpoints: nose down, center, nose up
+ * @param rudder Rudder setpoints: nose left, center, nose right
+ * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode
+ * @param pitch Pitch curve setpoints (every 25%)
+ * @param throttle Throttle curve setpoints (every 25%)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION;
+
+	i += put_array_by_index((const int8_t*)aileron, sizeof(uint16_t)*3, i, msg->payload); // Aileron setpoints: left, center, right
+	i += put_array_by_index((const int8_t*)elevator, sizeof(uint16_t)*3, i, msg->payload); // Elevator setpoints: nose down, center, nose up
+	i += put_array_by_index((const int8_t*)rudder, sizeof(uint16_t)*3, i, msg->payload); // Rudder setpoints: nose left, center, nose right
+	i += put_array_by_index((const int8_t*)gyro, sizeof(uint16_t)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode
+	i += put_array_by_index((const int8_t*)pitch, sizeof(uint16_t)*5, i, msg->payload); // Pitch curve setpoints (every 25%)
+	i += put_array_by_index((const int8_t*)throttle, sizeof(uint16_t)*5, i, msg->payload); // Throttle curve setpoints (every 25%)
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a radio_calibration struct into a 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 radio_calibration C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration)
+{
+	return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle);
+}
+
+/**
+ * @brief Send a radio_calibration message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param aileron Aileron setpoints: left, center, right
+ * @param elevator Elevator setpoints: nose down, center, nose up
+ * @param rudder Rudder setpoints: nose left, center, nose right
+ * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode
+ * @param pitch Pitch curve setpoints (every 25%)
+ * @param throttle Throttle curve setpoints (every 25%)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle)
+{
+	mavlink_message_t msg;
+	mavlink_msg_radio_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, aileron, elevator, rudder, gyro, pitch, throttle);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE RADIO_CALIBRATION UNPACKING
+
+/**
+ * @brief Get field aileron from radio_calibration message
+ *
+ * @return Aileron setpoints: left, center, right
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload, sizeof(uint16_t)*3);
+	return sizeof(uint16_t)*3;
+}
+
+/**
+ * @brief Get field elevator from radio_calibration message
+ *
+ * @return Elevator setpoints: nose down, center, nose up
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)*3, sizeof(uint16_t)*3);
+	return sizeof(uint16_t)*3;
+}
+
+/**
+ * @brief Get field rudder from radio_calibration message
+ *
+ * @return Rudder setpoints: nose left, center, nose right
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3, sizeof(uint16_t)*3);
+	return sizeof(uint16_t)*3;
+}
+
+/**
+ * @brief Get field gyro from radio_calibration message
+ *
+ * @return Tail gyro mode/gain setpoints: heading hold, rate mode
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3, sizeof(uint16_t)*2);
+	return sizeof(uint16_t)*2;
+}
+
+/**
+ * @brief Get field pitch from radio_calibration message
+ *
+ * @return Pitch curve setpoints (every 25%)
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*2, sizeof(uint16_t)*5);
+	return sizeof(uint16_t)*5;
+}
+
+/**
+ * @brief Get field throttle from radio_calibration message
+ *
+ * @return Throttle curve setpoints (every 25%)
+ */
+static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, uint16_t* r_data)
+{
+
+	memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*2+sizeof(uint16_t)*5, sizeof(uint16_t)*5);
+	return sizeof(uint16_t)*5;
+}
+
+/**
+ * @brief Decode a radio_calibration message into a struct
+ *
+ * @param msg The message to decode
+ * @param radio_calibration C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration)
+{
+	mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron);
+	mavlink_msg_radio_calibration_get_elevator(msg, radio_calibration->elevator);
+	mavlink_msg_radio_calibration_get_rudder(msg, radio_calibration->rudder);
+	mavlink_msg_radio_calibration_get_gyro(msg, radio_calibration->gyro);
+	mavlink_msg_radio_calibration_get_pitch(msg, radio_calibration->pitch);
+	mavlink_msg_radio_calibration_get_throttle(msg, radio_calibration->throttle);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/mavlink_msg_request_rc_channels.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,101 @@
+// MESSAGE REQUEST_RC_CHANNELS PACKING
+
+#define MAVLINK_MSG_ID_REQUEST_RC_CHANNELS 221
+
+typedef struct __mavlink_request_rc_channels_t 
+{
+	uint8_t enabled; ///< True: start sending data; False: stop sending data
+
+} mavlink_request_rc_channels_t;
+
+
+
+/**
+ * @brief Pack a request_rc_channels 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 enabled True: start sending data; False: stop sending data
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_request_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS;
+
+	i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a request_rc_channels message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param enabled True: start sending data; False: stop sending data
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_request_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS;
+
+	i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a request_rc_channels struct into a 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 request_rc_channels C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_request_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_rc_channels_t* request_rc_channels)
+{
+	return mavlink_msg_request_rc_channels_pack(system_id, component_id, msg, request_rc_channels->enabled);
+}
+
+/**
+ * @brief Send a request_rc_channels message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param enabled True: start sending data; False: stop sending data
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_request_rc_channels_send(mavlink_channel_t chan, uint8_t enabled)
+{
+	mavlink_message_t msg;
+	mavlink_msg_request_rc_channels_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE REQUEST_RC_CHANNELS UNPACKING
+
+/**
+ * @brief Get field enabled from request_rc_channels message
+ *
+ * @return True: start sending data; False: stop sending data
+ */
+static inline uint8_t mavlink_msg_request_rc_channels_get_enabled(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Decode a request_rc_channels message into a struct
+ *
+ * @param msg The message to decode
+ * @param request_rc_channels C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_request_rc_channels_decode(const mavlink_message_t* msg, mavlink_request_rc_channels_t* request_rc_channels)
+{
+	request_rc_channels->enabled = mavlink_msg_request_rc_channels_get_enabled(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/mavlink_msg_ualberta_sys_status.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,135 @@
+// MESSAGE UALBERTA_SYS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_UALBERTA_SYS_STATUS 222
+
+typedef struct __mavlink_ualberta_sys_status_t 
+{
+	uint8_t mode; ///< System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+	uint8_t nav_mode; ///< Navigation mode, see UALBERTA_NAV_MODE ENUM
+	uint8_t pilot; ///< Pilot mode, see UALBERTA_PILOT_MODE
+
+} mavlink_ualberta_sys_status_t;
+
+
+
+/**
+ * @brief Pack a ualberta_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 mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+ * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
+ * @param pilot Pilot mode, see UALBERTA_PILOT_MODE
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ualberta_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS;
+
+	i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM
+	i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE
+
+	return mavlink_finalize_message(msg, system_id, component_id, i);
+}
+
+/**
+ * @brief Pack a ualberta_sys_status message
+ * @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 was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+ * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
+ * @param pilot Pilot mode, see UALBERTA_PILOT_MODE
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ualberta_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
+{
+	uint16_t i = 0;
+	msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS;
+
+	i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+	i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM
+	i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE
+
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
+}
+
+/**
+ * @brief Encode a ualberta_sys_status struct into a 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 ualberta_sys_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ualberta_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ualberta_sys_status_t* ualberta_sys_status)
+{
+	return mavlink_msg_ualberta_sys_status_pack(system_id, component_id, msg, ualberta_sys_status->mode, ualberta_sys_status->nav_mode, ualberta_sys_status->pilot);
+}
+
+/**
+ * @brief Send a ualberta_sys_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+ * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
+ * @param pilot Pilot mode, see UALBERTA_PILOT_MODE
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ualberta_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
+{
+	mavlink_message_t msg;
+	mavlink_msg_ualberta_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, pilot);
+	mavlink_send_uart(chan, &msg);
+}
+
+#endif
+// MESSAGE UALBERTA_SYS_STATUS UNPACKING
+
+/**
+ * @brief Get field mode from ualberta_sys_status message
+ *
+ * @return System mode, see UALBERTA_AUTOPILOT_MODE ENUM
+ */
+static inline uint8_t mavlink_msg_ualberta_sys_status_get_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload)[0];
+}
+
+/**
+ * @brief Get field nav_mode from ualberta_sys_status message
+ *
+ * @return Navigation mode, see UALBERTA_NAV_MODE ENUM
+ */
+static inline uint8_t mavlink_msg_ualberta_sys_status_get_nav_mode(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Get field pilot from ualberta_sys_status message
+ *
+ * @return Pilot mode, see UALBERTA_PILOT_MODE
+ */
+static inline uint8_t mavlink_msg_ualberta_sys_status_get_pilot(const mavlink_message_t* msg)
+{
+	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
+}
+
+/**
+ * @brief Decode a ualberta_sys_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param ualberta_sys_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ualberta_sys_status_decode(const mavlink_message_t* msg, mavlink_ualberta_sys_status_t* ualberta_sys_status)
+{
+	ualberta_sys_status->mode = mavlink_msg_ualberta_sys_status_get_mode(msg);
+	ualberta_sys_status->nav_mode = mavlink_msg_ualberta_sys_status_get_nav_mode(msg);
+	ualberta_sys_status->pilot = mavlink_msg_ualberta_sys_status_get_pilot(msg);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Module_Communication/MAVlink/include/ualberta/ualberta.h	Wed Mar 19 09:27:19 2014 +0000
@@ -0,0 +1,79 @@
+/** @file
+ *	@brief MAVLink comm protocol.
+ *	@see http://qgroundcontrol.org/mavlink/
+ *	 Generated on Friday, August 5 2011, 07:37 UTC
+ */
+#ifndef UALBERTA_H
+#define UALBERTA_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_UALBERTA
+
+
+#include "../common/common.h"
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 0
+#endif
+
+// ENUM DEFINITIONS
+
+/** @brief  Available autopilot modes for ualberta uav */
+enum UALBERTA_AUTOPILOT_MODE
+{
+	MODE_MANUAL_DIRECT=0, /*  */
+	MODE_MANUAL_SCALED=1, /*  */
+	MODE_AUTO_PID_ATT=2, /*  */
+	MODE_AUTO_PID_VEL=3, /*  */
+	MODE_AUTO_PID_POS=4, /*  */
+	UALBERTA_AUTOPILOT_MODE_ENUM_END
+};
+
+/** @brief  Navigation filter mode */
+enum UALBERTA_NAV_MODE
+{
+	NAV_AHRS_INIT=0,
+	NAV_AHRS=1, /*  */
+	NAV_INS_GPS_INIT=2, /*  */
+	NAV_INS_GPS=3, /*  */
+	UALBERTA_NAV_MODE_ENUM_END
+};
+
+/** @brief  Mode currently commanded by pilot */
+enum UALBERTA_PILOT_MODE
+{
+	PILOT_MANUAL=0, /*  */
+	PILOT_AUTO=1, /*  */
+	PILOT_ROTO=2, /*  */
+	UALBERTA_PILOT_MODE_ENUM_END
+};
+
+
+// MESSAGE DEFINITIONS
+
+#include "./mavlink_msg_nav_filter_bias.h"
+#include "./mavlink_msg_radio_calibration.h"
+#include "./mavlink_msg_ualberta_sys_status.h"
+
+
+// MESSAGE LENGTHS
+
+#undef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 42, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
+
+#ifdef __cplusplus
+}
+#endif
+#endif
--- a/main.cpp	Wed Mar 19 09:18:53 2014 +0000
+++ b/main.cpp	Wed Mar 19 09:27:19 2014 +0000
@@ -1,3 +1,54 @@
+#define MAVLINK_TEST 1
+
+#if MAVLINK_TEST
+
+#include "mbed.h"
+#include "xbee.h"
+#include "MAVLink_API/MAVLink_API.h"
+#include "MAVlink/include/common/common.h"
+#include "mbos.h"
+#include "os.h"
+ 
+Serial pc(USBTX, USBRX);
+mavLink_API mvlk(2.0);
+mbos os(3, 2); //os just for compiling
+//xbee myXbee(p9, p10, p11);
+ 
+ 
+ int main() {
+
+     pc.baud(38400);
+
+    while(1){
+        if(mvlk.messageReadyToBeSent)
+        {
+            for(int i = 0 ; i < mvlk.len ; i++){
+                pc.putc(mvlk.buf[i]);
+            }
+            mvlk.messageReadyToBeSent = false;
+        }
+        while(pc.readable()){
+            mvlk.getMessage(pc.getc());
+        }
+        //pc.printf("size : %d\n", len);
+        //myXbee.SendData((char*)buf, (int)len);
+        //pc.puts((const char*)buf);
+        //for(int i = 0 ; i < len ; i++){
+            //pc.putc(buf[i]);
+        //}
+        //pc.putc(buf[len-2]);
+        
+        wait(1.0); 
+    }
+
+    /*for(int i = 0 ; i < len ; i++){
+            pc.printf("%x ", buf[i]);
+    }
+    pc.printf("\n\r");*/
+}
+//uart0_send(buf, len);
+#else
+
  /* Copyright (c) 2012 - 2013 Gaëtan PLEYBER
  *
  * THIS SOFTWARE IS PROVIDED BY THE AUTHOR "AS IS" AND ANY EXPRESS OR IMPLIED 
@@ -101,3 +152,5 @@
         if(os.GetEvent() & COMMUNICATION_EVENT) led3 = !led3;
    }
 }*/
+
+#endif