Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Files at this revision

API Documentation at this revision

Comitter:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Commit message:
Updated documentation

Changed in this revision

Actuators/Actuators.cpp Show annotated file Show diff for this revision Revisions of this file
Actuators/Actuators.h Show annotated file Show diff for this revision Revisions of this file
Actuators/Servo.lib Show annotated file Show diff for this revision Revisions of this file
Actuators/Steering/Steering.cpp Show annotated file Show diff for this revision Revisions of this file
Actuators/Steering/Steering.h Show annotated file Show diff for this revision Revisions of this file
Config/Config.cpp Show annotated file Show diff for this revision Revisions of this file
Config/Config.h Show annotated file Show diff for this revision Revisions of this file
Estimation/CartPosition/CartPosition.cpp Show annotated file Show diff for this revision Revisions of this file
Estimation/CartPosition/CartPosition.h Show annotated file Show diff for this revision Revisions of this file
Estimation/GeoPosition/GeoPosition.cpp Show annotated file Show diff for this revision Revisions of this file
Estimation/GeoPosition/GeoPosition.h Show annotated file Show diff for this revision Revisions of this file
Estimation/Mapping/Mapping.cpp Show annotated file Show diff for this revision Revisions of this file
Estimation/Mapping/Mapping.h Show annotated file Show diff for this revision Revisions of this file
Estimation/Matrix/Matrix.cpp Show annotated file Show diff for this revision Revisions of this file
Estimation/Matrix/Matrix.h Show annotated file Show diff for this revision Revisions of this file
Estimation/kalman.c Show annotated file Show diff for this revision Revisions of this file
Estimation/kalman.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ardupilotmega/ardupilotmega.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ardupilotmega/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ardupilotmega/mavlink_msg_sensor_offsets.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/checksum.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/common.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_action.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_action_ack.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_attitude.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_auth_key.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_boot.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_change_operator_control.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_change_operator_control_ack.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_command.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_command_ack.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_control_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_debug.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_debug_vect.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_full_state.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_global_position.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_global_position_int.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_local_origin_set.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_raw.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_raw_int.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_raw_ugv.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_set_global_origin.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_gps_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_hil_controls.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_hil_state.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_local_position.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_local_position_setpoint.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_local_position_setpoint_set.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_manual_control.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_named_value_float.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_named_value_int.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_nav_controller_output.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_object_detection_event.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_optical_flow.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_param_request_list.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_param_request_read.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_param_set.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_param_value.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_ping.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_position_target.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_raw_imu.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_raw_pressure.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_rc_channels_override.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_rc_channels_raw.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_rc_channels_scaled.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_request_data_stream.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_safety_allowed_area.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_safety_set_allowed_area.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_scaled_imu.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_scaled_pressure.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_servo_output_raw.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_altitude.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_mode.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_nav_mode.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_state_correction.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_statustext.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_sys_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_system_time.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_system_time_utc.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_vfr_hud.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_ack.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_clear_all.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_count.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_current.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_reached.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_request.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_request_list.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/common/mavlink_msg_waypoint_set_current.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/mavlink_bridge.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/mavlink_types.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/minimal/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/minimal/mavlink_msg_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/minimal/minimal.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_attitude_control.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_aux_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_brief_feature.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_encapsulated_data.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_global_vision_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_image_available.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_image_trigger_control.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_image_triggered.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_marker.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_pattern_detected.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_point_of_interest.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_position_control_offset_set.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_raw_aux.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_set_cam_shutter.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_vision_position_estimate.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_vision_speed_estimate.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_visual_odometry.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_watchdog_process_info.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/mavlink_msg_watchdog_process_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/pixhawk/pixhawk.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/protocol.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_air_data.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_cpu_load.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_data_log.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_diagnostic.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_gps_date_time.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_mid_lvl_cmds.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_sensor_bias.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_slugs_action.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/mavlink_msg_slugs_navigation.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/slugs/slugs.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/mavlink.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/mavlink_msg_nav_filter_bias.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/mavlink_msg_radio_calibration.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/mavlink_msg_request_rc_channels.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/mavlink_msg_ualberta_sys_status.h Show annotated file Show diff for this revision Revisions of this file
MAVlink/include/ualberta/ualberta.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/diskio.c Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/diskio.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/ff.c Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/ff.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/ffconf.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Core/integer.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATDirHandle.cpp Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATDirHandle.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATFileHandle.cpp Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATFileHandle.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATFileSystem.cpp Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/FATFileSystem/Interface/FATFileSystem.h Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/SDHCFileSystem.cpp Show annotated file Show diff for this revision Revisions of this file
SDFileSystem/SDHCFileSystem.h Show annotated file Show diff for this revision Revisions of this file
Schedule.lib Show annotated file Show diff for this revision Revisions of this file
Sensors/Camera/Camera.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Camera/Camera.h Show annotated file Show diff for this revision Revisions of this file
Sensors/GPS/GPS.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/GPS/GPS.h Show annotated file Show diff for this revision Revisions of this file
Sensors/GPS/TinyGPS/TinyGPS.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/GPS/TinyGPS/TinyGPS.h Show annotated file Show diff for this revision Revisions of this file
Sensors/GPS/TinyGPS/types.h Show annotated file Show diff for this revision Revisions of this file
Sensors/HMC5843/HMC5843.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/HMC5843/HMC5843.h Show annotated file Show diff for this revision Revisions of this file
Sensors/IncrementalEncoder/IncrementalEncoder.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/IncrementalEncoder/IncrementalEncoder.h Show annotated file Show diff for this revision Revisions of this file
Sensors/L3G4200D/L3G4200D.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/L3G4200D/L3G4200D.h Show annotated file Show diff for this revision Revisions of this file
Sensors/LSM303DLM.lib Show annotated file Show diff for this revision Revisions of this file
Sensors/Sensors.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Sensors.h Show annotated file Show diff for this revision Revisions of this file
SimpleFilter.lib Show annotated file Show diff for this revision Revisions of this file
SystemState.h Show annotated file Show diff for this revision Revisions of this file
UI/Beep/Beep.cpp Show annotated file Show diff for this revision Revisions of this file
UI/Beep/Beep.h Show annotated file Show diff for this revision Revisions of this file
UI/Buttons/Buttons.cpp Show annotated file Show diff for this revision Revisions of this file
UI/Buttons/Buttons.h Show annotated file Show diff for this revision Revisions of this file
UI/Buttons/DebounceIn.lib Show annotated file Show diff for this revision Revisions of this file
UI/Buttons/PinDetect.lib Show annotated file Show diff for this revision Revisions of this file
UI/LCD/Bargraph.cpp Show annotated file Show diff for this revision Revisions of this file
UI/LCD/Bargraph.h Show annotated file Show diff for this revision Revisions of this file
UI/LCD/GPSStatus.cpp Show annotated file Show diff for this revision Revisions of this file
UI/LCD/GPSStatus.h Show annotated file Show diff for this revision Revisions of this file
UI/LCD/lcd.c Show annotated file Show diff for this revision Revisions of this file
UI/LCD/lcd.h Show annotated file Show diff for this revision Revisions of this file
UI/Menu/Menu.cpp Show annotated file Show diff for this revision Revisions of this file
UI/Menu/Menu.h Show annotated file Show diff for this revision Revisions of this file
UI/SerialGraphicLCD/SerialGraphicLCD.cpp Show annotated file Show diff for this revision Revisions of this file
UI/SerialGraphicLCD/SerialGraphicLCD.h Show annotated file Show diff for this revision Revisions of this file
UI/shell.c Show annotated file Show diff for this revision Revisions of this file
UI/shell.h Show annotated file Show diff for this revision Revisions of this file
Watchdog.lib Show annotated file Show diff for this revision Revisions of this file
debug.h Show annotated file Show diff for this revision Revisions of this file
globals.h Show annotated file Show diff for this revision Revisions of this file
logging/logging.c Show annotated file Show diff for this revision Revisions of this file
logging/logging.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
mbed.bld Show annotated file Show diff for this revision Revisions of this file
updater.c Show annotated file Show diff for this revision Revisions of this file
updater.h Show annotated file Show diff for this revision Revisions of this file
util.c Show annotated file Show diff for this revision Revisions of this file
util.h Show annotated file Show diff for this revision Revisions of this file
diff -r 000000000000 -r 826c6171fc1b Actuators/Actuators.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Actuators/Actuators.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,48 @@
+#include "mbed.h"
+#include "Servo.h"
+#include "Config.h"
+
+extern Config config;
+
+Servo steering(p21);                    // Steering Servo
+Servo throttle(p22);                    // ESC
+int escMax=520;                         // Servo setting for max speed
+
+#define THROTTLE_CENTER 0.4
+
+void initSteering()
+{
+    // Setup steering servo
+    steering = config.steerZero;
+    // TODO: 3 parameterize this in config file
+    steering.calibrate(0.005, 45.0); 
+}
+
+
+void initThrottle()
+{
+    throttle = (float)config.escZero/1000.0;
+    // TODO: 3 parameterize this in config file
+    throttle.calibrate(0.001, 45.0); 
+}
+
+void setThrottle(int value)
+{
+    throttle = ((float)value)/1000.0;
+}
+
+void setSteering(float steerAngle)
+{
+    // Convert steerAngle to servo value
+    // Testing determined near linear conversion between servo ms setting and steering angle
+    // up to 20*.  Assumes a particular servo library with range = 0.005
+    // In that case, f(SA) = servoPosition = 0.500 + SA/762.5
+    // between 20 and 24* the slope is approximately 475
+    // What if we ignore the linearity and just set to a max angle
+    // also range is 0.535-0.460 --> slope = 800
+    // steering = 0.500 + (double) steerAngle / 762.5;
+    //
+    // TODO: 1 parameterize through config
+    steering = 0.500 + (double) steerAngle / 808.0;
+}
+    
diff -r 000000000000 -r 826c6171fc1b Actuators/Actuators.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Actuators/Actuators.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,13 @@
+#ifndef __ACTUATORS_H
+#define __ACTUATORS_H
+
+/** Abstraction of steering and throttle control
+ *
+ */
+
+void initSteering(void);
+void initThrottle(void);
+void setThrottle(int value);
+void setSteering(float steerAngle);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Actuators/Servo.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Actuators/Servo.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/simon/code/Servo/#36b69a7ced07
diff -r 000000000000 -r 826c6171fc1b Actuators/Steering/Steering.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Actuators/Steering/Steering.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,157 @@
+#include "Steering.h"
+#include "math.h"
+
+/** create a new steering calculator for a particular vehicle
+ *
+ */
+Steering::Steering(float wheelbase, float track)
+    : _wheelbase(wheelbase)
+    , _track(track)
+    , _intercept(2.0)
+{
+}
+
+void Steering::setIntercept(float intercept)
+{
+    _intercept = intercept;
+}
+
+/** Calculate a steering angle based on relative bearing
+ *
+ */
+float Steering::calcSA(float theta) {
+    return calcSA(theta, -1.0); // call with no limit
+}
+
+/** calcSA
+ * minRadius -- radius limit (minRadius < 0 disables limiting)
+ */
+float Steering::calcSA(float theta, float minRadius) {
+    float radius;
+    float SA;
+    bool neg = (theta < 0);
+
+    // I haven't had time to work out why the equation is slightly offset such
+    // that negative angle produces slightly less steering angle
+    //
+    if (neg) theta = -theta;
+    
+    // The equation peaks out at 90* so clamp theta artifically to 90, so that
+    // if theta is actually > 90, we select max steering
+    if (theta > 90.0) theta = 90.0;
+
+    // Compute |radius| based on intercept distance and specified angle with extra gain to 
+    // overcome steering slop, misalignment, sidehills, etc.
+    radius = _intercept / ( 2 * sin(angle_radians(theta)) );
+    
+    if (minRadius > 0) {
+        if (radius < minRadius) radius = minRadius;
+    }
+
+    // Now calculate steering angle based on wheelbase and track width
+    SA = angle_degrees(asin(_wheelbase / (radius - _track/2)));
+    // The above ignores the effect of speed on required steering angle.
+    // Even when under the limits of traction, understeer means more angle
+    // is required to achieve a turn at higher speeds than lower speeds.
+    // To consider this, we'd need to measure the understeer gradient of
+    // the vehicle (thanks to Project240 for this insight) and include
+    // that in the calculation.
+
+    if (neg) SA = -SA;
+
+    return SA;
+}
+
+/**
+ * Bxy - robot coordinates
+ * Axy - previous waypoint coords
+ * Cxy - next waypoint coords
+ */
+float Steering::crossTrack(float Bx, float By, float Ax, float Ay, float Cx, float Cy)
+{
+  // Compute rise for prev wpt to bot; or compute vector offset by A(x,y)
+  float Rx = (Bx - Ax);
+  // compute run for prev wpt to bot; or compute vector offset by A(x,y)
+  float Ry = (By - Ay);
+  // dx is the run for the path
+  float dx = Cx - Ax;
+  // dy is the rise for the path
+  float dy = Cy - Ay;
+  // this is hypoteneuse length squared
+  float ACd2 = dx*dx+dy*dy;
+  // length of hyptoenuse
+  float ACd = sqrtf( ACd2 );
+  
+  float Rd = Rx*dx + Ry*dy;  
+  float t = Rd / ACd2;
+  // nearest point on current segment
+  float Nx = Ax + dx*t; 
+  float Ny = Ay + dy*t;  
+  // Cross track error
+  float NBx = Nx-Bx;
+  float NBy = Ny-By;
+  float cte = sqrtf(NBx*NBx + NBy*NBy);
+  
+  return cte;
+}
+
+
+
+float Steering::purePursuitSA(float hdg, float Bx, float By, float Ax, float Ay, float Cx, float Cy)
+{
+  float SA;
+
+  // Compute rise for prev wpt to bot; or compute vector offset by A(x,y)
+  float Rx = (Bx - Ax);
+  // compute run for prev wpt to bot; or compute vector offset by A(x,y)
+  float Ry = (By - Ay);
+  // dx is the run for the path
+  float dx = Cx - Ax;
+  // dy is the rise for the path
+  float dy = Cy - Ay;
+  // this is hypoteneuse length squared
+  float ACd2 = dx*dx+dy*dy;
+  // length of hyptoenuse
+  float ACd = sqrtf( ACd2 );
+  
+  float Rd = Rx*dx + Ry*dy;  
+  float t = Rd / ACd2;
+  // nearest point on current segment
+  float Nx = Ax + dx*t; 
+  float Ny = Ay + dy*t;  
+  // Cross track error
+  float NBx = Nx-Bx;
+  float NBy = Ny-By;
+  float cte = sqrtf(NBx*NBx + NBy*NBy);
+    float NGd;
+
+  float myLookAhead;
+  
+  if (cte <= _intercept) {
+    myLookAhead = _intercept;
+  } else {
+    myLookAhead = _intercept + cte;
+  }
+  
+  NGd = sqrt( myLookAhead*myLookAhead - cte*cte );
+  float Gx = NGd * dx/ACd + Nx;
+  float Gy = NGd * dy/ACd + Ny;
+  
+  float hdgr = hdg*PI/180;
+  
+  float BGx = (Gx-Bx)*cos(hdgr) - (Gy-By)*sin(hdgr);
+  float c = (2 * BGx) / (myLookAhead*myLookAhead);
+
+  float radius;
+  
+  if (c != 0) {
+    radius = 1/c;
+  } else {
+    radius = 999999.0;
+  }
+
+  // Now calculate steering angle based on wheelbase and track width
+  SA = angle_degrees(asin(_wheelbase / (radius - _track/2)));
+
+  return SA;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Actuators/Steering/Steering.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Actuators/Steering/Steering.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,66 @@
+
+#define PI 3.141592653589
+
+/** A class for managing steering angle calculations based on current and desired heading
+ *  and specified intercept distance along the new path.  
+ *
+ *  See Notebook entry: http://mbed.org/users/shimniok/notebook/smooth-steering-for-rc-car/
+ */
+class Steering
+{
+  public:
+    /** create a new steering calculator
+     *
+     * @param wheelbase vehicle wheelbase
+     * @param track vehicle track width
+     * @param intercept new course intercept distance
+     */
+    Steering(float wheelbase, float track);
+
+    /** set intercept distance
+     * @param intercept distance along new course at which turn arc will intercept
+     */
+    void setIntercept(float intercept);
+
+    /** convert course change to average steering angle
+     * assumes Ackerman steering, with track and wheelbase
+     * and course intercept distance specified.
+     *
+     * See notebook: http://mbed.org/users/shimniok/notebook/smooth-steering-for-rc-car/
+     *
+     * @param theta relative bearing of the new course
+     * @returns steering angle in degrees
+     */ 
+    float calcSA(float theta);
+
+    /** convert course change to average steering angle
+     * assumes Ackerman steering, with track and wheelbase
+     * and course intercept distance specified. Also, |radius| of turn is limited to limit
+     *
+     * See notebook: http://mbed.org/users/shimniok/notebook/smooth-steering-for-rc-car/
+     *
+     * @param theta relative bearing of the new course
+     * @param limit is the limit of the turn circle radius (absolute value)
+     * @returns steering angle in degrees
+     */ 
+    float calcSA(float theta, float limit);
+
+    /** compute steering angle based on pure pursuit algorithm
+     */
+    float purePursuitSA(float hdg, float Bx, float By, float Ax, float Ay, float Bx, float By);
+    
+    /** Compute cross track error given last waypoint, next waypoint, and robot coordinates
+     * @returns cross track error
+     */
+    float crossTrack(float Bx, float By, float Ax, float Ay, float Bx, float By);
+    
+  private:
+
+    inline static float angle_radians(float deg) {return (PI/180.0)*deg;}
+
+    inline static float angle_degrees(float rad) {return (180/PI)*rad;}
+
+    float _wheelbase;
+    float _track;
+    float _intercept;
+};
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Config/Config.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Config/Config.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,151 @@
+#define MAXBUF 64
+
+#include "Config.h"
+#include "SDHCFileSystem.h"
+#include "GeoPosition.h"
+#include "globals.h"
+#include "util.h"
+
+extern Serial pc;
+
+// TODO: 3: mod waypoints to include speed after waypoint
+
+Config::Config()
+{
+    // not much to do here, yet.
+}
+
+// load configuration from filesystem
+bool Config::load()
+{
+    LocalFileSystem local("etc");         // Create the local filesystem under the name "local"
+    FILE *fp;
+    char buf[MAXBUF];   // buffer to read in data
+    char tmp[MAXBUF];   // temp buffer
+    char *p;
+    double lat, lon;
+    bool declFound = false;
+    bool confStatus = false;
+    
+    // Just to be safe let's wait
+    //wait(2.0);
+
+    pc.printf("opening config file...\n");
+    
+    fp = fopen("/etc/config.txt", "r");
+    if (fp == 0) {
+        pc.printf("Could not open config.txt\n");
+    } else {
+        wptCount = 0;
+        declination = 0.0;
+        while (!feof(fp)) {
+            fgets(buf, MAXBUF-1, fp);
+            p = split(tmp, buf, MAXBUF, ',');           // split off the first field
+            switch (tmp[0]) {
+                case 'B' :
+                    p = split(tmp, p, MAXBUF, ',');     // threshold distance for curb avoid
+                    curbThreshold = cvstof(tmp);
+                    p = split(tmp, p, MAXBUF, ',');     // steering gain for curb avoid
+                    curbGain = cvstof(tmp);
+                    break;
+                case 'W' :                              // Waypoint
+                    p = split(tmp, p, MAXBUF, ',');     // split off the latitude to tmp
+                    lat = cvstof(tmp);
+                    p = split(tmp, p, MAXBUF, ',');     // split off the longitude to tmp
+                    lon = cvstof(tmp);
+                    if (wptCount < MAXWPT) {
+                        wpt[wptCount].set(lat, lon);
+                        wptCount++;
+                    }
+                    break;
+                case 'G' :                              // GPS
+                    p = split(tmp, p, MAXBUF, ',');
+                    gpsBaud = atoi(tmp);                // baud rate for gps
+                    p = split(tmp, p, MAXBUF, ',');
+                    gpsType = atoi(tmp);
+                    break;
+                case 'Y' :                              // Gyro Bias
+                    p = split(tmp, p, MAXBUF, ',');     // split off the declination to tmp
+                    gyroBias = (float) cvstof(tmp);
+                    break;
+                case 'D' :                              // Compass Declination
+                    p = split(tmp, p, MAXBUF, ',');     // split off the declination to tmp
+                    declination = (float) cvstof(tmp);
+                    declFound = true;
+                    break;
+                case 'N' :                                  // Navigation and Turning    
+                    p = split(tmp, p, MAXBUF, ',');
+                    interceptDist = (float) cvstof(tmp);    // intercept distance for steering algorithm
+                    p = split(tmp, p, MAXBUF, ',');
+                    waypointDist = (float) cvstof(tmp);     // distance before waypoint switch
+                    p = split(tmp, p, MAXBUF, ',');
+                    brakeDist = (float) cvstof(tmp);        // distance at which braking starts
+                    p = split(tmp, p, MAXBUF, ',');
+                    minRadius = (float) cvstof(tmp);        // minimum turning radius
+                    break;
+                case 'M' :                              // Magnetometer
+                    for (int i=0; i < 3; i++) {
+                        p = split(tmp, p, MAXBUF, ',');
+                        magOffset[i] = (float) cvstof(tmp);
+                        pc.printf("magOffset[%d]: %.2f\n", i, magOffset[i]);
+                    }
+                    for (int i=0; i < 3; i++) {
+                        p = split(tmp, p, MAXBUF, ',');
+                        magScale[i] = (float) cvstof(tmp);
+                        pc.printf("magScale[%d]: %.2f\n", i, magScale[i]);
+                    }                    
+                case 'R' : // Steering configuration
+                    p = split(tmp, p, MAXBUF, ',');
+                    steerZero = cvstof(tmp);            // servo center setting
+                    p = split(tmp, p, MAXBUF, ',');
+                    steerGain = cvstof(tmp);            // steering angle multiplier
+                    p = split(tmp, p, MAXBUF, ',');
+                    steerGainAngle = cvstof(tmp);       // angle below which steering gain takes effect
+                    p = split(tmp, p, MAXBUF, ',');
+                    cteKi = cvstof(tmp);                // integral term for cross track
+                    p = split(tmp, p, MAXBUF, ',');
+                    usePP = ( atoi(tmp) == 1 );         // use pure pursuit algorithm
+                    break;
+                case 'S' :                              // Throttle configuration
+                    p = split(tmp, p, MAXBUF, ',');
+                    escMin = atoi(tmp);                 // minimum esc (brake) setting
+                    p = split(tmp, p, MAXBUF, ',');     
+                    escZero = atoi(tmp);                // esc center/zero setting
+                    p = split(tmp, p, MAXBUF, ',');     
+                    escMax = atoi(tmp);                 // maximum esc setting
+                    p = split(tmp, p, MAXBUF, ',');   
+                    topSpeed = cvstof(tmp);             // desired top speed
+                    p = split(tmp, p, MAXBUF, ',');   
+                    turnSpeed = cvstof(tmp);            // speed to use within brake distance of waypoint
+                    p = split(tmp, p, MAXBUF, ',');
+                    startSpeed = cvstof(tmp);            // speed to use at start
+                    p = split(tmp, p, MAXBUF, ',');
+                    speedKp = cvstof(tmp);              // speed PID: proportional gain
+                    p = split(tmp, p, MAXBUF, ',');     
+                    speedKi = cvstof(tmp);              // speed PID: integral gain
+                    p = split(tmp, p, MAXBUF, ',');     
+                    speedKd = cvstof(tmp);              // speed PID: derivative gain
+    
+                    break;
+                case 'E' :
+                    p = split(tmp, p, MAXBUF, ',');     
+                    compassGain = (float) cvstof(tmp);  // not used (DCM)
+                    p = split(tmp, p, MAXBUF, ',');    
+                    yawGain = (float) cvstof(tmp);      // not used (DCM)
+                default :
+                    break;
+            } // switch
+        } // while
+
+        // Did we get the values we were looking for?
+        if (wptCount > 0 && declFound) {
+            confStatus = true;
+        }
+        
+    } // if fp
+    
+    if (fp != 0)
+        fclose(fp);
+
+    return confStatus;
+}
diff -r 000000000000 -r 826c6171fc1b Config/Config.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Config/Config.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,54 @@
+#ifndef __CONFIG_H
+#define __CONFIG_H
+
+#include "GeoPosition.h"
+#include "CartPosition.h"
+
+/** Text-based configuration; reads config file and stores in fields
+ */
+class Config {
+    public:
+        Config();
+
+        bool load();
+        
+        float interceptDist;    // used for course correction steering calculation
+        float waypointDist;     // distance threshold to waypoint
+        float brakeDist;        // braking distance
+        float declination;
+        float compassGain;      // probably don't need this anymore
+        float yawGain;          // probably don't need this anymore
+        GeoPosition wpt[10];    // Waypoints, lat/lon coords
+        CartPosition cwpt[10];  // Waypoints, cartesian coords
+        unsigned int wptCount;  // number of active waypoints
+        int escMin;             // minimum ESC value; brake
+        int escZero;            // zero throttle
+        int escMax;             // max throttle
+        float topSpeed;         // top speed to achieve on the straights
+        float turnSpeed;        // speed for turns
+        float startSpeed;       // speed for start 
+        float minRadius;        // minimum turning radius (calculated)
+        float speedKp;          // Speed PID proportional gain
+        float speedKi;          // Speed PID integral gain
+        float speedKd;          // Speed PID derivative gain
+        float steerZero;        // zero steering aka center point
+        float steerGain;        // gain factor for steering algorithm
+        float steerGainAngle;   // angle below which steering gain takes effect
+        float cteKi;            // cross track error integral gain
+        bool usePP;             // use pure pursuit algorithm? 
+        float curbThreshold;    // distance at which curb avoid takes place
+        float curbGain;         // gain of curb avoid steering
+        // acceleration profile?
+        // braking profile?
+        float gyroBias;     // this needs to be 3d
+        // float gyroScale[3];
+        float magOffset[3];
+        float magScale[3];
+        // float accelOffset[3];
+        // float accelScale[3];
+        int gpsType;
+        int gpsBaud;
+        
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Estimation/CartPosition/CartPosition.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/CartPosition/CartPosition.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,58 @@
+#include "mbed.h" // debug
+#include "CartPosition.h"
+
+#define PI 3.1415926535897932
+
+CartPosition::CartPosition(void)
+{
+    set(0,0);
+}
+
+CartPosition::CartPosition(float x, float y)
+{
+    set(x,y);
+}
+
+// TODO: 3 fix _x, _y to be private with getters setters
+
+void CartPosition::set(CartPosition p)
+{
+    _x = p._x;
+    _y = p._y;
+}
+
+void CartPosition::set(float x, float y)
+{
+    _x = x;
+    _y = y;
+}
+
+
+float CartPosition::bearingTo(CartPosition to)
+{
+    // x and y aren't backwards; it's to correct for the differences between
+    // geometry and navigation. In the former, angles are measured from the x axis,
+    // in the latter, from the y axis.
+    return 180/PI * atan2(to._x-_x, to._y-_y); 
+}
+
+
+float CartPosition::distanceTo(CartPosition to)
+{
+    float dx = to._x-_x;
+    float dy = to._y-_y;
+    
+    return sqrt( dx*dx + dy*dy );
+}
+
+void CartPosition::move(float bearing, float distance)
+{
+    // x and y aren't backwards; it's to correct for the differences between
+    // geometry and navigation. In the former, angles are measured from the x axis,
+    // in the latter, from the y axis.
+    float r = bearing * PI / 180;
+    _x += distance * sin( r );
+    _y += distance * cos( r );
+    
+    return;
+}
diff -r 000000000000 -r 826c6171fc1b Estimation/CartPosition/CartPosition.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/CartPosition/CartPosition.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,43 @@
+#ifndef __CARTPOSITION_H
+#define __CARTPOSITION_H
+
+/** Geographical position and calculation based on cartesian coordinates
+ */
+class CartPosition {
+public:
+    /** Create a new cartesian coordinate object
+     */
+    CartPosition(void);
+    /** Create a new cartesian coordinate object
+     * @param x sets x coordinate
+     * @param y sets y coordinate 
+     */
+    CartPosition(float x, float y);
+    /** Sets coordinates for object
+     * @param x sets x coordinate
+     * @param y sets y coordinate 
+     */
+    void set(float x, float y);
+    /** Sets coordinates for object
+     * @param p sets coordinates of this object to that of p
+     */
+    void set(CartPosition p);
+    /** Computes bearing to a position from this position
+     * @param to is the coordinate to which we're calculating bearing
+     */
+    float bearingTo(CartPosition to);
+    /** Computes distance to a position from this position
+     * @param to is the coordinate to which we're calculating distance
+     */
+    float distanceTo(CartPosition to);
+    /** Computes the new coordinates for this object given a bearing and distance
+     * @param bearing is the direction traveled
+     * @distance is the distance traveled
+     */
+    void move(float bearing, float distance);
+    /** x coordinate of this object */
+    float _x;
+    /** y coordinate of this object */
+    float _y;
+};
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Estimation/GeoPosition/GeoPosition.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/GeoPosition/GeoPosition.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,196 @@
+#include "GeoPosition.h"
+#include <math.h>
+
+// Earth's mean radius in meters
+#define EARTHRADIUS 6371000.0
+// TODO: 2 altitude
+
+GeoPosition::GeoPosition(): _R(EARTHRADIUS), _latitude(0.0), _longitude(0.0)
+{
+}
+
+GeoPosition::GeoPosition(double latitude, double longitude): _R(EARTHRADIUS), _latitude(latitude), _longitude(longitude)
+{
+}
+
+/*
+double GeoPosition::easting()
+{
+}
+
+double GeoPosition::northing()
+{
+}
+*/
+
+double GeoPosition::latitude()
+{
+    return _latitude;
+}
+
+double GeoPosition::longitude()
+{
+    return _longitude;
+}
+
+void GeoPosition::set(double latitude, double longitude)
+{
+    _latitude = latitude;
+    _longitude = longitude;
+}
+
+void GeoPosition::set(GeoPosition pos)
+{
+    _latitude = pos.latitude();
+    _longitude = pos.longitude();
+}
+
+/*
+void GeoPosition::set(UTM coord)
+{
+}
+*/
+
+void GeoPosition::move(float course, float distance)
+{
+    double d = distance / _R;
+    double c = radians(course);
+    double rlat1 = radians(_latitude);
+    double rlon1 = radians(_longitude);
+
+    // Precompute to improve performance
+    double cd = cos(d);
+    double sd = sin(d);
+    double srlat1 = sin(rlat1);
+    double crlat1 = cos(rlat1);
+
+    double rlat2 = asin(srlat1*cd + crlat1*sd*cos(c));
+    double rlon2 = rlon1 + atan2(sin(c)*sd*crlat1, cd-srlat1*sin(rlat2));
+
+    _latitude  = degrees(rlat2);
+    _longitude = degrees(rlon2);
+
+    // bring back within the range -180 to +180
+    while (_longitude < -180.0) _longitude += 360.0;
+    while (_longitude > 180.0) _longitude -= 360.0;
+}
+
+/*
+void GeoPosition::move(Direction toWhere)
+{
+}
+
+Direction GeoPosition::direction(GeoPosition startingPoint)
+{
+}
+*/
+
+float GeoPosition::bearing(GeoPosition from)
+{
+    return bearingFrom(from);
+}
+
+float GeoPosition::bearingTo(GeoPosition to)
+{
+    double lat1 = radians(_latitude);
+    double lon1 = radians(_longitude);
+    double lat2 = radians(to.latitude());
+    double lon2 = radians(to.longitude());
+    double dLon = lon2 - lon1;
+
+    double y = sin(dLon) * cos(lat2);
+    double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(dLon);
+
+    return degrees(atan2(y, x)); 
+}
+
+/*
+JavaScript:    
+var y = Math.sin(dLon) * Math.cos(lat2);
+var x = Math.cos(lat1)*Math.sin(lat2) -
+        Math.sin(lat1)*Math.cos(lat2)*Math.cos(dLon);
+var brng = Math.atan2(y, x).toDeg();
+*/
+float GeoPosition::bearingFrom(GeoPosition from)
+{
+    double lat1 = radians(from.latitude());
+    double lon1 = radians(from.longitude());
+    double lat2 = radians(_latitude);
+    double lon2 = radians(_longitude);
+    double dLon = lon2 - lon1;
+
+    double y = sin(dLon) * cos(lat2);
+    double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(dLon);
+
+    return degrees(atan2(y, x)); 
+}
+
+/*
+float GeoPosition::bearing(LatLong startingPoint)
+{
+}
+
+float GeoPosition::bearing(UTM startingPoint)
+{
+}
+*/
+
+float GeoPosition::distance(GeoPosition from)
+{
+    return distanceFrom(from);
+}
+
+float GeoPosition::distanceTo(GeoPosition to)
+{
+    double lat1 = radians(_latitude);
+    double lon1 = radians(_longitude);
+    double lat2 = radians(to.latitude());
+    double lon2 = radians(to.longitude());
+    double dLat = lat2 - lat1;
+    double dLon = lon2 - lon1;
+
+    double a = sin(dLat/2.0) * sin(dLat/2.0) + 
+               cos(lat1) * cos(lat2) *
+               sin(dLon/2.0) * sin(dLon/2.0);
+    double c = 2.0 * atan2(sqrt(a), sqrt(1-a));
+    
+    return _R * c;
+}
+
+float GeoPosition::distanceFrom(GeoPosition from)
+{
+    double lat1 = radians(from.latitude());
+    double lon1 = radians(from.longitude());
+    double lat2 = radians(_latitude);
+    double lon2 = radians(_longitude);
+    double dLat = lat2 - lat1;
+    double dLon = lon2 - lon1;
+
+    double a = sin(dLat/2.0) * sin(dLat/2.0) + 
+               cos(lat1) * cos(lat2) *
+               sin(dLon/2.0) * sin(dLon/2.0);
+    double c = 2.0 * atan2(sqrt(a), sqrt(1-a));
+    
+    return _R * c;
+}
+
+/*
+float GeoPosition::distance(LatLong startingPoint)
+{
+}
+
+float GeoPosition::distance(UTM startingPoint)
+{
+}
+*/
+
+void GeoPosition::setTimestamp(int time) {
+    _time = time;
+}
+
+int GeoPosition::getTimestamp(void) {
+    return _time;
+}
+
+
+    
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Estimation/GeoPosition/GeoPosition.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/GeoPosition/GeoPosition.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,106 @@
+#ifndef __GEOPOSITION_H
+#define __GEOPOSITION_H
+
+#ifndef _PI
+#define _PI 3.141592653
+#endif
+
+#define degrees(x) ((x)*180/_PI)
+#define radians(x) ((x)*_PI/180)
+
+/** Geographical position and calculation. Most of this comes from http://www.movable-type.co.uk/scripts/latlong.html
+ *
+ */
+class GeoPosition {
+public:
+
+    /** Create a new emtpy position object
+     *
+     */
+    GeoPosition();
+
+    /** Create a new position with the specified latitude and longitude. See set()
+     *
+     *  @param latitude is the latitude to set
+     *  @param longitude is the longitude to set
+     */
+    GeoPosition(double latitude, double longitude);
+    
+    /** Get the position's latitude
+     *
+     *  @returns the position's latitude
+     */
+    double latitude();
+    
+    /** Get the position's longitude
+     *
+     *  @returns the position's longitude
+     */
+    double longitude();
+    
+    /** Set the position's location to another position's coordinates
+     *
+     *  @param pos is another position from which coordinates will be copied
+     */
+    void set(GeoPosition pos);
+    
+    /** Set the position's location to the specified coordinates
+     *
+     *  @param latitude is the new latitude to set
+     *  @param longitude is the new longitude to set
+     */
+    void set(double latitude, double longitude);
+    
+    /** Move the location of the position by the specified distance and in
+     *  the specified direction
+     *
+     *  @param course is the direction of movement in degrees, absolute not relative
+     *  @param distance is the distance of movement along the specified course in meters
+     */
+    void move(float course, float distance);
+
+    /** Get the bearing from the specified origin position to this position.  To get
+     *  relative bearing, subtract the result from your heading.
+     *
+     *  @param from is the position from which to calculate bearing
+     *  @returns the bearing in degrees
+     */
+    float bearing(GeoPosition from);
+
+    float bearingFrom(GeoPosition from);
+
+    float bearingTo(GeoPosition to);
+    
+    /** Get the distance from the specified origin position to this position
+     *
+     *  @param from is the position from which to calculate distance
+     *  @returns the distance in meters
+     */
+    float distance(GeoPosition from);
+    
+    float distanceTo(GeoPosition to);
+    
+    float distanceFrom(GeoPosition from);
+    
+    /** Set an arbitrary timestamp on the position
+     *
+     * @param timestamp is an integer timestamp, eg., seconds, milliseconds, or whatever
+     */
+     void setTimestamp(int time);
+
+    /** Return a previously set timestamp on the position
+     *
+     * @returns the timestamp (e.g., seconds, milliseconds, etc.)
+     */     
+     int getTimestamp(void);
+
+private:
+    double _R;          /** Earth's mean radius */
+    double _latitude;   /** The position's latitude */
+    double _longitude;  /** The position's longitude */
+    double _northing;   /** The position's UTM northing coordinate */
+    double _easting;    /** The position's UTM easting coordinate */
+    int _time;          /** Timestamp */
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Estimation/Mapping/Mapping.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/Mapping/Mapping.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,80 @@
+#include "mbed.h" // debugging
+#include "Mapping.h"
+
+/*
+ * Provide a series of lat/lon coordinates/waypoints, and the object
+ * automatically generates a bounding rectangle, and determines how to
+ * translate between lat/lon and cartesian x/y
+ */
+void Mapping::init(int count, GeoPosition *p)
+{
+    double latMin = 360;
+    double latMax = -360;
+    double lonMin = 360;
+    double lonMax = -360;
+    
+    // Find minimum and maximum lat/lon
+    for (int i=0; i < count; i++, p++) {
+        //fprintf(stdout, "%d (%.6f, %.6f)\n", i, p->latitude(), p->longitude());
+        if (p->latitude() > latMax)
+            latMax = p->latitude();
+        if (p->latitude() < latMin)
+            latMin = p->latitude();
+            
+        if (p->longitude() > lonMax)
+            lonMax = p->longitude();
+        if (p->longitude() < lonMin)
+            lonMin = p->longitude();
+    }
+
+    // Set the arbitrary cartesian origin to southwest corner
+    lonZero = lonMin;
+    latZero = latMin;
+
+    //fprintf(stdout, "min: (%.6f, %.6f)\n", latMin, lonMin);
+    //fprintf(stdout, "max: (%.6f, %.6f)\n", latMax, lonMax);
+
+    // Three positions required to scale
+    GeoPosition sw(latMin, lonMin);
+    GeoPosition nw(latMax, lonMin);
+    GeoPosition se(latMin, lonMax);
+    
+    // Find difference between lat and lon min/max
+    float dlat = (latMax - latMin);
+    float dlon = (lonMax - lonMin);
+    
+    //fprintf(stdout, "dlat=%.6f dlon=%.6f\n", dlat, dlon);
+    
+    // Compute scale based on distances between edges of rectangle
+    // and difference between min/max lat and min/max lon
+    lonToX = sw.distanceTo(se) / dlon;
+    latToY = sw.distanceTo(nw) / dlat;
+
+    fprintf(stdout, "lonToX=%.10f\nlatToY=%.10f\n", lonToX, latToY);
+
+    return;    
+}
+
+void Mapping::geoToCart(GeoPosition pos, CartPosition *cart)
+{
+    cart->set( lonToX * (pos.longitude() - lonZero),
+               latToY * (pos.latitude() - latZero) );
+
+    return;
+}
+
+void Mapping::cartToGeo(float x, float y, GeoPosition *pos)
+{
+    pos->set( (y / latToY) + latZero, 
+              (x / lonToX) + lonZero);
+
+    return; 
+}
+
+void Mapping::cartToGeo(CartPosition cart, GeoPosition *pos)
+{
+    cartToGeo(cart._x, cart._y, pos);
+    
+    return;
+}
+
diff -r 000000000000 -r 826c6171fc1b Estimation/Mapping/Mapping.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/Mapping/Mapping.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,39 @@
+#ifndef __MAPPING_H
+#define __MAPPING_H
+
+#include "GeoPosition.h"
+#include "CartPosition.h"
+
+/** Maps GeoPosition latitude/longitude to CartPosition cartesian x,y
+ */
+class Mapping {
+public:
+    /** Initialize mapping with a number of GeoPosition coordinates
+     *  The maximum/minimum values for lat/lon are then used to form
+     *  four coordinates and linear interpolation is used to map lat/lon to y/x
+     */
+    void init(int count, GeoPosition *p);
+    /** Convert a GeoPosition to a CartPosition
+     * @param pos is the lat/lon pair
+     * @returns cart is the converted cartesian coordinate pair
+     */
+    void geoToCart(GeoPosition pos, CartPosition *cart);
+    /** Convert a GeoPosition to a CartPosition
+     * @param x is the cartesian x coordinate
+     * @param y is the cartesian y coordinate
+     * @returns pos is the converted GeoPosition lat/lon coordinate pair
+     */
+    void cartToGeo(float x, float y, GeoPosition *pos);
+    /** Convert a GeoPosition to a CartPosition
+     * @param cart is the x,y cartesian coordinate pair
+     * @returns pos is the converted GeoPosition lat/lon coordinate pair
+     */
+    void cartToGeo(CartPosition cart, GeoPosition *pos);
+
+private:
+    double lonToX;
+    double latToY;
+    double latZero;
+    double lonZero;
+};
+#endif
diff -r 000000000000 -r 826c6171fc1b Estimation/Matrix/Matrix.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/Matrix/Matrix.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,235 @@
+#include <stdio.h>
+#include "Matrix.h"
+
+unsigned int matrix_error = 0;
+
+void Vector_Cross_Product(float C[3], float A[3], float B[3])
+{
+    C[0] = (A[1] * B[2]) - (A[2] * B[1]);
+    C[1] = (A[2] * B[0]) - (A[0] * B[2]);
+    C[2] = (A[0] * B[1]) - (A[1] * B[0]);
+  
+    return;
+}
+
+void Vector_Scale(float C[3], float A[3], float b)
+{
+    for (int m = 0; m < 3; m++)
+        C[m] = A[m] * b;
+        
+    return;
+}
+
+float Vector_Dot_Product(float A[3], float B[3])
+{
+    float result = 0.0;
+
+    for (int i = 0; i < 3; i++) {
+        result += A[i] * B[i];
+    }
+    
+    return result;
+}
+
+void Vector_Add(float C[3], float A[3], float B[3])
+{
+    for (int m = 0; m < 3; m++)
+        C[m] = A[m] + B[m];
+        
+    return;
+}
+
+void Vector_Add(float C[3][3], float A[3][3], float B[3][3])
+{
+    for (int m = 0; m < 3; m++)
+        for (int n = 0; n < 3; n++)
+            C[m][n] = A[m][n] + B[m][n];
+}
+
+void Matrix_Add(float C[3][3], float A[3][3], float B[3][3])
+{
+    for (int i = 0; i < 3; i++) {
+        for (int j = 0; j < 3; j++) {
+           C[i][j] = A[i][j] + B[i][j];
+        }
+    }
+}
+
+void Matrix_Add(int n, int m, float *C, float *A, float *B)
+{
+    for (int i = 0; i < n*m; i++) {
+       C[i] = A[i] + B[i];
+    }
+}
+
+void Matrix_Subtract(int n, int m, float *C, float *A, float *B)
+{
+    for (int i = 0; i < n*m; i++) {
+       C[i] = A[i] - B[i];
+    }
+}
+
+
+
+// grabbed from MatrixMath library for Arduino
+// http://arduino.cc/playground/Code/MatrixMath
+// E.g., the equivalent Octave script:
+//   A=[x; y; z];
+//   B=[xx xy xz; yx yy yz; zx xy zz]; 
+//   C=A*B;
+// Would be called like this:
+//   Matrix_Mulitply(1, 3, 3, C, A, B);
+//
+void Matrix_Multiply(int m, int p, int n, float *C, float *A, float *B)
+{
+    // A = input matrix (m x p)
+    // B = input matrix (p x n)
+    // m = number of rows in A
+    // p = number of columns in A = number of rows in B
+    // n = number of columns in B
+    // C = output matrix = A*B (m x n)
+    for (int i=0; i < m; i++) {
+        for(int j=0; j < n; j++) {
+            C[n*i+j] = 0;
+            for (int k=0; k < p; k++) {
+                C[i*n+j] += A[i*p+k] * B[k*n+j];
+            }
+        }
+    }
+        
+    return;
+}
+
+void Matrix_Multiply(float C[3][3], float A[3][3], float B[3][3])
+{
+    for (int i = 0; i < 3; i++) {
+        for (int j = 0; j < 3; j++) {
+            C[i][j] = 0;
+            for (int k = 0; k < 3; k++) {
+               C[i][j] += A[i][k] * B[k][j];
+            }
+        }
+    }
+}
+
+
+void Matrix_Transpose(int n, int m, float *C, float *A)
+{
+    for (int i=0; i < n; i++) {
+        for (int j=0; j < m; j++) {
+            C[j*n+i] = A[i*m+j];
+        }
+    }
+}
+
+#define fabs(x) (((x) < 0) ? -x : x)
+
+// grabbed from MatrixMath library for Arduino
+// http://arduino.cc/playground/Code/MatrixMath
+//Matrix Inversion Routine
+// * This function inverts a matrix based on the Gauss Jordan method.
+// * Specifically, it uses partial pivoting to improve numeric stability.
+// * The algorithm is drawn from those presented in 
+//     NUMERICAL RECIPES: The Art of Scientific Computing.
+// * NOTE: The argument is ALSO the result matrix, meaning the input matrix is REPLACED
+void Matrix_Inverse(int n, float *A)
+{
+    // A = input matrix AND result matrix
+    // n = number of rows = number of columns in A (n x n)
+    int pivrow=0;   // keeps track of current pivot row
+    int k,i,j;        // k: overall index along diagonal; i: row index; j: col index
+    int pivrows[n]; // keeps track of rows swaps to undo at end
+    float tmp;        // used for finding max value and making column swaps
+    
+    for (k = 0; k < n; k++) {
+        // find pivot row, the row with biggest entry in current column
+        tmp = 0;
+        for (i = k; i < n; i++) {
+            if (fabs(A[i*n+k]) >= tmp) {    // 'Avoid using other functions inside abs()?'
+                tmp = fabs(A[i*n+k]);
+                pivrow = i;
+            }
+        }
+        
+        // check for singular matrix
+        if (A[pivrow*n+k] == 0.0f) {
+            matrix_error |= SINGULAR_MATRIX;
+            //fprintf(stdout, "Inversion failed due to singular matrix");
+            return;
+        }
+        
+        // Execute pivot (row swap) if needed
+        if (pivrow != k) {
+            // swap row k with pivrow
+            for (j = 0; j < n; j++) {
+                tmp = A[k*n+j];
+                A[k*n+j] = A[pivrow*n+j];
+                A[pivrow*n+j] = tmp;
+            }
+        }
+        pivrows[k] = pivrow;    // record row swap (even if no swap happened)
+        
+        tmp = 1.0f/A[k*n+k];    // invert pivot element
+        A[k*n+k] = 1.0f;        // This element of input matrix becomes result matrix
+        
+        // Perform row reduction (divide every element by pivot)
+        for (j = 0; j < n; j++) {
+            A[k*n+j] = A[k*n+j]*tmp;
+        }
+        
+        // Now eliminate all other entries in this column
+        for (i = 0; i < n; i++) {
+            if (i != k) {
+                tmp = A[i*n+k];
+                A[i*n+k] = 0.0f;  // The other place where in matrix becomes result mat
+                for (j = 0; j < n; j++) {
+                    A[i*n+j] = A[i*n+j] - A[k*n+j]*tmp;
+                }
+            }
+        }
+    }
+    
+    // Done, now need to undo pivot row swaps by doing column swaps in reverse order
+    for (k = n-1; k >= 0; k--) {
+        if (pivrows[k] != k) {
+            for (i = 0; i < n; i++) {
+                tmp = A[i*n+k];
+                A[i*n+k] = A[i*n+pivrows[k]];
+                A[i*n+pivrows[k]] = tmp;
+            }
+        }
+    }
+    return;
+}
+
+
+void Matrix_Copy(int n, int m, float *C, float *A)
+{
+    for (int i=0; i < n*m; i++)
+        C[i] = A[i];
+}
+
+void Matrix_print(int n, int m, float *A, const char *name)
+{
+    fprintf(stdout, "%s=[", name);
+    for (int i=0; i < n; i++) {
+        for (int j=0; j < m; j++) {
+            fprintf(stdout, "%5.5f", A[i*m+j]);
+            if (j < m-1) fprintf(stdout, ", ");
+        }
+        if (i < n-1) fprintf(stdout, "; ");
+    }
+    fprintf(stdout, "]\n");
+}  
+
+
+void Vector_Print(float A[3], const char *name)
+{
+    fprintf(stdout, "%s=[ ", name);
+    for (int i=0; i < 3; i++)
+        fprintf(stdout, "%5.5f ", A[i]);
+    fprintf(stdout, "]\n");
+    
+    return;
+}
+
diff -r 000000000000 -r 826c6171fc1b Estimation/Matrix/Matrix.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/Matrix/Matrix.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,94 @@
+#ifndef __DCM_MATRIX_H
+#define __DCM_MATRIX_H
+
+/** Matrix math library */
+
+#define SINGULAR_MATRIX     (1<<0)
+#define ERR1                (1<<1)
+#define ERR2                (1<<2)
+#define ERR3                (1<<3)
+
+/** Take cross product of two 3x1 vectors: v1 x v2 = vectorOut
+ * @param v1 is the first vector
+ * @param v2 is the second vector
+ * @returns vectorOut = v1 x v2
+ */
+void Vector_Cross_Product(float vectorOut[3], float v1[3], float v2[3]);
+
+/** Multiple 3x1 vector by scalar: vectorOut = vectorIn times scale2
+ * @param vectorIn the vector
+ * @param scale2 is the scalar
+ * @returns vectorOut the result
+ */
+void Vector_Scale(float vectorOut[3], float vectorIn[3], float scale2);
+
+/** TDot product of two 3x1 vectors vector1 . vector2
+ * @param vector1 is the first vector
+ * @param vector2 is the second vector
+ * @returns float result of dot product
+ */
+float Vector_Dot_Product(float vector1[3], float vector2[3]);
+
+/** Adds two 3x1 vectors: vectorOut = vectorIn1 + vectorIn2
+ * @param vectorIn1 is the first vector
+ * @param vectorIn2 is the second vector
+ * @returns vectorOut is the result of the addition
+ */
+void Vector_Add(float vectorOut[3], float vectorIn1[3], float vectorIn2[3]);
+
+/** Adds two 3x3 matrices: C = A + B
+ * @param A is the first vector
+ * @param B is the second vector
+ * @returns C is the result of the addition
+ */
+void Matrix_Add(float C[3][3], float A[3][3], float B[3][3]);
+
+/** Adds two n x m matrices: C = A + B
+ * @param A is the first vector
+ * @param B is the second vector
+ * @param n is the rows of A, B, C
+ * @param m is the columns of A, B, C
+ * @returns C is the result of the addition
+ */
+void Matrix_Add(int n, int m, float *C, float *A, float *B);
+
+void Matrix_Subtract(int n, int m, float *C, float *A, float *B);
+
+/** Multiplies two 3x3 matrices to get a third 3x3 matrix: c = ab
+ * @param a is the first vector
+ * @param b is the second vector
+ * @returns c as the result of the mutliplication
+ */
+void Matrix_Multiply(float c[3][3], float a[3][3], float b[3][3]);
+
+/** Multiplies two 3x3 matrices to get a third 3x3 matrix: c = ab
+ * @param A is the first matrix
+ * @param B is the second matrix
+ * @param n is the rows of A
+ * @param p is the columns of A and rows of B
+ * @param m is the columns of B
+ * @returns C as the result of the mutliplication
+ */
+void Matrix_Multiply(int n, int m, int p, float *C, float *A, float *B);
+
+void Matrix_Transpose(int n, int m, float *C, float *A);
+
+void Matrix_Inverse(int n, float *A);
+
+void Matrix_Inverse(int n, float *C, float *A);
+
+void Matrix_Copy(int n, int m, float *C, float *A);
+
+/** Prints out an m x m matrix
+ * @param A is the matrix to print
+ * @param name is the name to print out along with the vector
+ */
+void Matrix_print(int n, int m, float *A, const char *name);
+
+/** Prints out a 1 x 3 vector
+ * @param A is the 1 x 3 vector to print
+ * @param name is the name to print out along with the vector
+ */
+void Vector_Print(float A[3], const char *name);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Estimation/kalman.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/kalman.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,228 @@
+#include "mbed.h"
+#include "Matrix.h"
+
+#define DEBUG 1
+
+#define clamp360(x) ((((x) < 0) ? 360: 0) + fmod((x), 360))
+
+/*
+ * Kalman Filter Setup
+ */
+static float x[2]={ 0, 0 };                 // System State: hdg, hdg rate
+float z[2]={ 0, 0 };                        // measurements, hdg, hdg rate
+static float A[4]={ 1, 0, 0, 1};            // State transition matrix; A[1] should be dt
+static float H[4]={ 1, 0, 0, 1 };           // Observer matrix maps measurements to state transition
+float K[4]={ 0, 0, 0, 0 };                  // Kalman gain
+static float P[4]={ 1000, 0, 0, 1000 };     // Covariance matrix
+static float R[4]={ 3, 0, 0, 0.03 };        // Measurement noise, hdg, hdg rate
+static float Q[4]={ 0.01, 0, 0, 0.01 };     // Process noise matrix
+static float I[4]={ 1, 0, 0, 1 };           // Identity matrix
+
+float kfGetX(int i)
+{
+    return (i >= 0 && i < 2) ? x[i] : 0xFFFFFFFF;
+}
+
+/** headingKalmanInit
+ *
+ * initialize x, z, K, and P
+ */
+void headingKalmanInit(float x0)
+{
+    x[0] = x0;
+    x[1] = 0;
+
+    z[0] = 0;
+    z[1] = 0;
+
+    K[0] = 0; K[1] = 0;
+    K[2] = 0; K[3] = 0;
+    
+    P[0] = 1000; P[1] = 0;
+    P[2] = 0;    P[3] = 1000;
+}
+
+
+/* headingKalman 
+ *
+ * Implements a 1-dimensional, 1st order Kalman Filter
+ *
+ * That is, it deals with heading and heading rate (h and h') but no other
+ * state variables.  The state equations are:
+ *
+ *                     X    =    A       X^
+ * h = h + h'dt -->  | h  | = | 1 dt | | h  |
+ * h' = h'           | h' |   | 0  1 | | h' |
+ *
+ * Kalman Filtering is not that hard. If it's hard you haven't found the right
+ * teacher. Try taking CS373 from Udacity.com
+ *
+ * This notation is Octave (Matlab) syntax and is based on the Bishop-Welch
+ * paper and references the equation numbers in that paper.
+ * http://www.cs.unc.edu/~welch/kalman/kalmanIntro.html
+ *
+ * returns : current heading estimate
+ */
+float headingKalman(float dt, float Hgps, bool gps, float dHgyro, bool gyro)
+{
+    A[1] = dt;
+
+    /* Initialize, first time thru
+    x = H*z0
+    */
+
+    //fprintf(stdout, "gyro? %c  gps? %c\n", (gyro)?'Y':'N', (gps)?'Y':'N');
+            
+    // Depending on what sensor measurements we've gotten,
+    // switch between observer (H) matrices and measurement noise (R) matrices
+    // TODO: incorporate HDOP or sat count in R
+    if (gps) {
+        H[0] = 1.0;
+        z[0] = Hgps;
+    } else {
+        H[0] = 0;
+        z[0] = 0;
+    }
+
+    if (gyro) {
+        H[3] = 1.0;
+        z[1] = dHgyro;
+    } else {
+        H[3] = 0;
+        z[1] = 0;
+    }
+
+    //Matrix_print(2,2, A, "1. A");
+    //Matrix_print(2,2, P, "   P");
+    //Matrix_print(2,1, x, "   x");
+    //Matrix_print(2,1, K, "   K");
+    //Matrix_print(2,2, H, "2. H");
+    //Matrix_print(2,1, z, "   z");
+   
+   /**********************************************************************
+     * Predict
+     %
+     * In this step we "move" our state estimate according to the equation
+     *
+     * x = A*x; // Eq 1.9
+     ***********************************************************************/
+    float xp[2];
+    Matrix_Multiply(2,2,1, xp, A, x);
+    
+    //Matrix_print(2,1, xp, "3. xp");
+
+    /**********************************************************************
+     * We also have to "move" our uncertainty and add noise. Whenever we move,
+     * we lose certainty because of system noise.
+     *
+     * P = A*P*A' + Q; // Eq 1.10
+     ***********************************************************************/
+    float At[4];
+    Matrix_Transpose(2,2, At, A);
+    float AP[4];
+    Matrix_Multiply(2,2,2, AP, A, P);
+    float APAt[4];
+    Matrix_Multiply(2,2,2, APAt, AP, At);
+    Matrix_Add(2,2, P, APAt, Q);
+
+    //Matrix_print(2,2, P, "4. P");
+
+    /**********************************************************************
+     * Measurement aka Correct
+     * First, we have to figure out the Kalman Gain which is basically how
+     * much we trust the sensor measurement versus our prediction.
+     *
+     * K = P*H'*inv(H*P*H' + R);    // Eq 1.11
+     ***********************************************************************/
+    float Ht[4];
+    //Matrix_print(2,2, H,    "5. H");
+    Matrix_Transpose(2,2, Ht, H);
+    //Matrix_print(2,2, Ht,    "5. Ht");
+
+    float HP[2];
+    //Matrix_print(2,2, P,    "5. P");
+    Matrix_Multiply(2,2,2, HP, H, P);
+    //Matrix_print(2,2, HP,    "5. HP");
+
+    float HPHt[4];
+    Matrix_Multiply(2,2,2, HPHt, HP, Ht);
+    //Matrix_print(2,2, HPHt,    "5. HPHt");
+    
+    float HPHtR[4];
+    //Matrix_print(2,2, R,    "5. R");
+    Matrix_Add(2,2, HPHtR, HPHt, R);
+    //Matrix_print(2,2, HPHtR,    "5. HPHtR");
+
+    Matrix_Inverse(2, HPHtR);
+    //Matrix_print(2,2, HPHtR,    "5. HPHtR");
+
+    float PHt[2];
+    //Matrix_print(2,2, P,    "5. P");
+    //Matrix_print(2,2, Ht,    "5. Ht");
+    Matrix_Multiply(2,2,2, PHt, P, Ht);
+    //Matrix_print(2,2, PHt,    "5. PHt");
+    
+    Matrix_Multiply(2,2,2, K, PHt, HPHtR);
+    
+    //Matrix_print(2,2, K,    "5. K");
+        
+    /**********************************************************************
+     * Then we determine the discrepancy between prediction and measurement 
+     * with the "Innovation" or Residual: z-H*x, multiply that by the 
+     * Kalman gain to correct the estimate towards the prediction a little 
+     * at a time.
+     *
+     * x = x + K*(z-H*x);            // Eq 1.12
+     ***********************************************************************/
+    float Hx[2];
+    Matrix_Multiply(2,2,1, Hx, H, xp);
+
+    //Matrix_print(2,2, H, "6. H");
+    //Matrix_print(2,1, x, "6. x");
+    //Matrix_print(2,1, Hx, "6. Hx");
+    
+    float zHx[2];
+    Matrix_Subtract(2,1, zHx, z, Hx);
+
+    // At this point we need to be sure to correct heading to -180 to 180 range
+    if (zHx[0] > 180.0)   zHx[0] -= 360.0;
+    if (zHx[0] <= -180.0) zHx[0] += 360.0;
+
+    //Matrix_print(2,1, z, "6. z");
+    //Matrix_print(2,1, zHx, "6. zHx");
+    
+    float KzHx[2];
+    Matrix_Multiply(2,2,1, KzHx, K, zHx);
+
+    //Matrix_print(2,2, K, "6. K");
+    //Matrix_print(2,1, KzHx, "6. KzHx");
+    
+    Matrix_Add(2,1, x, xp, KzHx);
+
+    // Clamp to 0-360 range
+    while (x[0] < 0) x[0] += 360.0;
+    while (x[0] >= 360.0) x[0] -= 360.0;
+
+    //Matrix_print(2,1, x, "6. x");
+
+    /**********************************************************************
+     * We also have to adjust the certainty. With a new measurement, the 
+     * estimate certainty always increases.
+     *
+     * P = (I-K*H)*P;                // Eq 1.13
+     ***********************************************************************/
+    float KH[4];
+    //Matrix_print(2,2, K, "7. K");
+    Matrix_Multiply(2,2,2, KH, K, H);
+    //Matrix_print(2,2, KH, "7. KH");
+    float IKH[4];
+    Matrix_Subtract(2,2, IKH, I, KH);
+    //Matrix_print(2,2, IKH, "7. IKH");
+    float P2[4];
+    Matrix_Multiply(2,2,2, P2, IKH, P);
+    Matrix_Copy(2, 2, P, P2);
+
+    //Matrix_print(2,2, P, "7. P");
+
+    return x[0];
+}
diff -r 000000000000 -r 826c6171fc1b Estimation/kalman.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Estimation/kalman.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,11 @@
+#ifndef __KALMAN_H
+#define __KALMAN_H
+
+/** Implementation of 1st order, 2-state Kalman Filter for heading estimation
+ */
+ 
+float kfGetX(int i);
+void headingKalmanInit(float x0);
+float headingKalman(float dt, float Hgps, bool gps, float dHgyro, bool gyro);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ardupilotmega/ardupilotmega.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ardupilotmega/ardupilotmega.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ardupilotmega/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ardupilotmega/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ardupilotmega/mavlink_msg_sensor_offsets.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ardupilotmega/mavlink_msg_sensor_offsets.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/checksum.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/checksum.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/common.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/common.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_action.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_action.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_action_ack.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_action_ack.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_attitude.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_attitude.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_auth_key.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_auth_key.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_boot.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_boot.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_change_operator_control.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_change_operator_control.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_change_operator_control_ack.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_change_operator_control_ack.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_command.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_command.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_command_ack.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_command_ack.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_control_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_control_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_debug.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_debug.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_debug_vect.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_debug_vect.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_full_state.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_full_state.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_global_position.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_global_position.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_global_position_int.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_global_position_int.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_local_origin_set.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_local_origin_set.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_raw.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_raw.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_raw_int.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_raw_int.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_raw_ugv.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_raw_ugv.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_set_global_origin.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_set_global_origin.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_gps_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_gps_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_heartbeat.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_heartbeat.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_hil_controls.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_hil_controls.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_hil_state.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_hil_state.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_local_position.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_local_position.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_local_position_setpoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_local_position_setpoint.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_local_position_setpoint_set.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_local_position_setpoint_set.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_manual_control.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_manual_control.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_named_value_float.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_named_value_float.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_named_value_int.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_named_value_int.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_nav_controller_output.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_nav_controller_output.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_object_detection_event.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_object_detection_event.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_optical_flow.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_optical_flow.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_param_request_list.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_param_request_list.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_param_request_read.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_param_request_read.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_param_set.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_param_set.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_param_value.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_param_value.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_ping.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_ping.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_position_target.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_position_target.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_raw_imu.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_raw_imu.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_raw_pressure.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_raw_pressure.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_rc_channels_override.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_rc_channels_override.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_rc_channels_raw.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_rc_channels_raw.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_rc_channels_scaled.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_rc_channels_scaled.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_request_data_stream.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_request_data_stream.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_safety_allowed_area.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_safety_allowed_area.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_safety_set_allowed_area.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_safety_set_allowed_area.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_scaled_imu.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_scaled_imu.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_scaled_pressure.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_scaled_pressure.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_servo_output_raw.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_servo_output_raw.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_altitude.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_altitude.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_mode.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_mode.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_nav_mode.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_nav_mode.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_state_correction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_state_correction.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_statustext.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_statustext.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_sys_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_sys_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_system_time.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_system_time.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_system_time_utc.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_system_time_utc.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_vfr_hud.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_vfr_hud.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_ack.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_ack.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_clear_all.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_clear_all.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_count.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_count.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_current.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_current.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_reached.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_reached.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_request.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_request.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_request_list.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_request_list.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/common/mavlink_msg_waypoint_set_current.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/common/mavlink_msg_waypoint_set_current.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/mavlink_bridge.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/mavlink_bridge.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/mavlink_types.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/mavlink_types.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,251 @@
+#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_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_ */
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/minimal/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/minimal/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/minimal/mavlink_msg_heartbeat.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/minimal/mavlink_msg_heartbeat.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/minimal/minimal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/minimal/minimal.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_attitude_control.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_attitude_control.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_aux_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_aux_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_brief_feature.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_brief_feature.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_encapsulated_data.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_encapsulated_data.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_global_vision_position_estimate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_global_vision_position_estimate.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_image_available.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_image_available.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_image_trigger_control.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_image_trigger_control.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_image_triggered.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_image_triggered.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_marker.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_marker.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_pattern_detected.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_pattern_detected.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_point_of_interest.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_point_of_interest.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_position_control_offset_set.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_position_control_offset_set.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_raw_aux.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_raw_aux.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_set_cam_shutter.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_set_cam_shutter.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_vision_position_estimate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_vision_position_estimate.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_vision_speed_estimate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_vision_speed_estimate.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_visual_odometry.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_visual_odometry.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_watchdog_process_info.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_info.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/mavlink_msg_watchdog_process_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/mavlink_msg_watchdog_process_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/pixhawk/pixhawk.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/pixhawk/pixhawk.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/protocol.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/protocol.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,997 @@
+#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);
+    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;
+        }
+        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));
+        }
+        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_ */
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_air_data.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_air_data.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_cpu_load.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_cpu_load.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_data_log.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_data_log.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_diagnostic.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_diagnostic.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_gps_date_time.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_gps_date_time.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_mid_lvl_cmds.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_mid_lvl_cmds.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_sensor_bias.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_sensor_bias.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_slugs_action.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_slugs_action.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/mavlink_msg_slugs_navigation.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/mavlink_msg_slugs_navigation.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/slugs/slugs.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/slugs/slugs.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/mavlink.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/mavlink.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/mavlink_msg_nav_filter_bias.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/mavlink_msg_nav_filter_bias.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/mavlink_msg_radio_calibration.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/mavlink_msg_radio_calibration.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/mavlink_msg_request_rc_channels.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/mavlink_msg_request_rc_channels.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/mavlink_msg_ualberta_sys_status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/mavlink_msg_ualberta_sys_status.h	Wed Jun 20 14:57:48 2012 +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);
+}
diff -r 000000000000 -r 826c6171fc1b MAVlink/include/ualberta/ualberta.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MAVlink/include/ualberta/ualberta.h	Wed Jun 20 14:57:48 2012 +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
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/diskio.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/diskio.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,138 @@
+/*-----------------------------------------------------------------------*/
+/* Low level disk I/O module skeleton for FatFs     (C)ChaN, 2007        */
+/*-----------------------------------------------------------------------*/
+/* This is a stub disk I/O module that acts as front end of the existing */
+/* disk I/O modules and attach it to FatFs module with common interface. */
+/*-----------------------------------------------------------------------*/
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#include "diskio.h"
+
+DSTATUS disk_initialize(BYTE drv) 
+{
+    if (FATFileSystem::DriveArray[drv])
+    {
+        return (DSTATUS)FATFileSystem::DriveArray[drv]->disk_initialize();
+    }
+    else
+    {
+        return STA_NOINIT;
+    }
+}
+
+DSTATUS disk_status(BYTE drv) 
+{
+    if (FATFileSystem::DriveArray[drv])
+    {
+        return (DSTATUS)FATFileSystem::DriveArray[drv]->disk_status();
+    }
+    else
+    {
+        return STA_NOINIT;
+    }
+}
+
+DRESULT disk_read(BYTE drv, BYTE* buff, DWORD sector, BYTE count)
+{
+    if (FATFileSystem::DriveArray[drv])
+    {
+        return (DRESULT)FATFileSystem::DriveArray[drv]->disk_read((unsigned char*)buff,
+            (unsigned long)sector, (unsigned char)count);
+    }
+    else
+    {
+        return RES_NOTRDY;
+    }
+}
+
+#if _READONLY == 0
+DRESULT disk_write(BYTE drv, const BYTE* buff, DWORD sector, BYTE count)
+{
+    if (FATFileSystem::DriveArray[drv])
+    {
+        return (DRESULT)FATFileSystem::DriveArray[drv]->disk_write((const unsigned char*)buff,
+            (unsigned long)sector, (unsigned char)count);
+    }
+    else
+    {
+        return RES_NOTRDY;
+    }
+}
+#endif
+
+DRESULT disk_ioctl(BYTE drv, BYTE ctrl, void* buff)
+{
+    switch (ctrl)
+    {
+        case CTRL_SYNC:
+            if (FATFileSystem::DriveArray[drv])
+            {
+                return (DRESULT)FATFileSystem::DriveArray[drv]->disk_sync();
+            }
+            else
+            {
+                return RES_NOTRDY;
+            } 
+
+        case GET_SECTOR_SIZE:
+            if (FATFileSystem::DriveArray[drv])
+            {
+                WORD Result = FATFileSystem::DriveArray[drv]->disk_sector_size();
+                if (Result > 0)
+                {
+                    *((WORD*)buff) = Result;
+                    return RES_OK;
+                }
+                else
+                {
+                    return RES_ERROR;
+                }
+            }
+            else
+            {
+                return RES_NOTRDY;
+            }
+
+        case GET_SECTOR_COUNT:
+            if (FATFileSystem::DriveArray[drv])
+            {
+                DWORD Result = FATFileSystem::DriveArray[drv]->disk_sector_count();
+                if (Result > 0)
+                {
+                    *((DWORD*)buff) = Result;
+                    return RES_OK;
+                }
+                else
+                {
+                    return RES_ERROR;
+                }
+            }
+            else
+            {
+                return RES_NOTRDY;
+            }
+
+        case GET_BLOCK_SIZE:
+            if (FATFileSystem::DriveArray[drv])
+            {
+                DWORD Result = FATFileSystem::DriveArray[drv]->disk_block_size();
+                if (Result > 0)
+                {
+                    *((DWORD*)buff) = Result;
+                    return RES_OK;
+                }
+                else
+                {
+                    return RES_ERROR;
+                }
+            }
+            else
+            {
+                return RES_NOTRDY;
+            }
+
+        default:
+            return RES_PARERR;
+    }
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/diskio.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/diskio.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,57 @@
+/*-----------------------------------------------------------------------
+/  Low level disk interface module include file  R0.06   (C)ChaN, 2007
+/-----------------------------------------------------------------------*/
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#ifndef _DISKIO
+#define _DISKIO
+
+#define _READONLY   0
+#define _USE_IOCTL  1
+
+#include "integer.h"
+#include "FATFileSystem.h"
+#include <stdio.h>
+
+/* Status of Disk Functions */
+typedef BYTE    DSTATUS;
+#define STA_NOINIT  0x01    /* Drive not initialized */
+#define STA_NODISK  0x02    /* No medium in the drive */
+#define STA_PROTECT 0x04    /* Write protected */
+/* Results of Disk Functions */
+typedef enum
+{
+    RES_OK = 0,     /* 0: Successful */
+    RES_ERROR,      /* 1: R/W Error */
+    RES_WRPRT,      /* 2: Write Protected */
+    RES_NOTRDY,     /* 3: Not Ready */
+    RES_PARERR      /* 4: Invalid Parameter */
+} DRESULT;
+
+/* Prototypes for disk control functions */
+DSTATUS disk_initialize (BYTE);
+DSTATUS disk_status (BYTE);
+DRESULT disk_read (BYTE, BYTE*, DWORD, BYTE);
+#if    _READONLY == 0
+DRESULT disk_write (BYTE, const BYTE*, DWORD, BYTE);
+#endif
+DRESULT disk_ioctl (BYTE, BYTE, void*);
+/* Command code for disk_ioctrl() */
+#define CTRL_SYNC           0   /* Mandatory for read/write configuration */
+#define GET_SECTOR_COUNT    1   /* Mandatory for only f_mkfs() */
+#define GET_SECTOR_SIZE     2
+#define GET_BLOCK_SIZE      3   /* Mandatory for only f_mkfs() */
+#define CTRL_POWER          4
+#define CTRL_LOCK           5
+#define CTRL_EJECT          6
+#define MMC_GET_TYPE        10  /* MMC/SDC command */
+#define MMC_GET_CSD         11
+#define MMC_GET_CID         12
+#define MMC_GET_OCR         13
+#define MMC_GET_SDSTAT      14
+#define ATA_GET_REV         20  /* ATA/CF command */
+#define ATA_GET_MODEL       21
+#define ATA_GET_SN          22
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/ff.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/ff.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,3555 @@
+/*----------------------------------------------------------------------------/
+/  FatFs - FAT file system module  R0.08                  (C)ChaN, 2010
+/-----------------------------------------------------------------------------/
+/ FatFs module is a generic FAT file system module for small embedded systems.
+/ This is a free software that opened for education, research and commercial
+/ developments under license policy of following terms.
+/
+/  Copyright (C) 2010, ChaN, all right reserved.
+/
+/ * The FatFs module is a free software and there is NO WARRANTY.
+/ * No restriction on use. You can use, modify and redistribute it for
+/   personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
+/ * Redistributions of source code must retain the above copyright notice.
+/
+/-----------------------------------------------------------------------------/
+/ Feb 26,'06 R0.00  Prototype.
+/
+/ Apr 29,'06 R0.01  First stable version.
+/
+/ Jun 01,'06 R0.02  Added FAT12 support.
+/                   Removed unbuffered mode.
+/                   Fixed a problem on small (<32M) partition.
+/ Jun 10,'06 R0.02a Added a configuration option (_FS_MINIMUM).
+/
+/ Sep 22,'06 R0.03  Added f_rename().
+/                   Changed option _FS_MINIMUM to _FS_MINIMIZE.
+/ Dec 11,'06 R0.03a Improved cluster scan algorithm to write files fast.
+/                   Fixed f_mkdir() creates incorrect directory on FAT32.
+/
+/ Feb 04,'07 R0.04  Supported multiple drive system.
+/                   Changed some interfaces for multiple drive system.
+/                   Changed f_mountdrv() to f_mount().
+/                   Added f_mkfs().
+/ Apr 01,'07 R0.04a Supported multiple partitions on a physical drive.
+/                   Added a capability of extending file size to f_lseek().
+/                   Added minimization level 3.
+/                   Fixed an endian sensitive code in f_mkfs().
+/ May 05,'07 R0.04b Added a configuration option _USE_NTFLAG.
+/                   Added FSInfo support.
+/                   Fixed DBCS name can result FR_INVALID_NAME.
+/                   Fixed short seek (<= csize) collapses the file object.
+/
+/ Aug 25,'07 R0.05  Changed arguments of f_read(), f_write() and f_mkfs().
+/                   Fixed f_mkfs() on FAT32 creates incorrect FSInfo.
+/                   Fixed f_mkdir() on FAT32 creates incorrect directory.
+/ Feb 03,'08 R0.05a Added f_truncate() and f_utime().
+/                   Fixed off by one error at FAT sub-type determination.
+/                   Fixed btr in f_read() can be mistruncated.
+/                   Fixed cached sector is not flushed when create and close
+/                   without write.
+/
+/ Apr 01,'08 R0.06  Added fputc(), fputs(), fprintf() and fgets().
+/                   Improved performance of f_lseek() on moving to the same
+/                   or following cluster.
+/
+/ Apr 01,'09 R0.07  Merged Tiny-FatFs as a buffer configuration option.
+/                   Added long file name support.
+/                   Added multiple code page support.
+/                   Added re-entrancy for multitask operation.
+/                   Added auto cluster size selection to f_mkfs().
+/                   Added rewind option to f_readdir().
+/                   Changed result code of critical errors.
+/                   Renamed string functions to avoid name collision.
+/ Apr 14,'09 R0.07a Separated out OS dependent code on reentrant cfg.
+/                   Added multiple sector size support.
+/ Jun 21,'09 R0.07c Fixed f_unlink() can return FR_OK on error.
+/                   Fixed wrong cache control in f_lseek().
+/                   Added relative path feature.
+/                   Added f_chdir() and f_chdrive().
+/                   Added proper case conversion to extended char.
+/ Nov 03,'09 R0.07e Separated out configuration options from ff.h to ffconf.h.
+/                   Fixed f_unlink() fails to remove a sub-dir on _FS_RPATH.
+/                   Fixed name matching error on the 13 char boundary.
+/                   Added a configuration option, _LFN_UNICODE.
+/                   Changed f_readdir() to return the SFN with always upper
+/                   case on non-LFN cfg.
+/
+/ May 15,'10 R0.08  Added a memory configuration option. (_USE_LFN)
+/                   Added file lock feature. (_FS_SHARE)
+/                   Added fast seek feature. (_USE_FASTSEEK)
+/                   Changed some types on the API, XCHAR->TCHAR.
+/                   Changed fname member in the FILINFO structure on Unicode cfg.
+/                   String functions support UTF-8 encoding files on Unicode cfg.
+/---------------------------------------------------------------------------*/
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#include "ff.h"            /* FatFs configurations and declarations */
+#include "diskio.h"        /* Declarations of low level disk I/O functions */
+
+
+/*--------------------------------------------------------------------------
+
+   Module Private Definitions
+
+---------------------------------------------------------------------------*/
+
+#if _FATFS != 8085
+#error Wrong include file (ff.h).
+#endif
+
+
+/* FAT sub-type boundaries */
+/* Note that the FAT spec by Microsoft says 4085 but Windows works with 4087! */
+#define MIN_FAT16    4086    /* Minimum number of clusters for FAT16 */
+#define    MIN_FAT32    65526    /* Minimum number of clusters for FAT32 */
+
+
+/* Definitions corresponds to multiple sector size */
+#if _MAX_SS == 512        /* Single sector size */
+#define    SS(fs)    512U
+#elif _MAX_SS == 1024 || _MAX_SS == 2048 || _MAX_SS == 4096    /* Multiple sector size */
+#define    SS(fs)    ((fs)->ssize)
+#else
+#error Wrong sector size.
+#endif
+
+
+/* Reentrancy related */
+#if _FS_REENTRANT
+#if _USE_LFN == 1
+#error Static LFN work area must not be used in re-entrant configuration.
+#endif
+#define    ENTER_FF(fs)        { if (!lock_fs(fs)) return FR_TIMEOUT; }
+#define    LEAVE_FF(fs, res)    { unlock_fs(fs, res); return res; }
+
+#else
+#define    ENTER_FF(fs)
+#define LEAVE_FF(fs, res)    return res
+
+#endif
+
+#define    ABORT(fs, res)        { fp->flag |= FA__ERROR; LEAVE_FF(fs, res); }
+
+
+/* Character code support macros */
+#define IsUpper(c)    (((c)>='A')&&((c)<='Z'))
+#define IsLower(c)    (((c)>='a')&&((c)<='z'))
+#define IsDigit(c)    (((c)>='0')&&((c)<='9'))
+
+#if _DF1S        /* Code page is DBCS */
+
+#ifdef _DF2S    /* Two 1st byte areas */
+#define IsDBCS1(c)    (((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E) || ((BYTE)(c) >= _DF2S && (BYTE)(c) <= _DF2E))
+#else            /* One 1st byte area */
+#define IsDBCS1(c)    ((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E)
+#endif
+
+#ifdef _DS3S    /* Three 2nd byte areas */
+#define IsDBCS2(c)    (((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E) || ((BYTE)(c) >= _DS3S && (BYTE)(c) <= _DS3E))
+#else            /* Two 2nd byte areas */
+#define IsDBCS2(c)    (((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E))
+#endif
+
+#else            /* Code page is SBCS */
+
+#define IsDBCS1(c)    0
+#define IsDBCS2(c)    0
+
+#endif /* _DF1S */
+
+
+/* Name status flags */
+#define NS            11        /* Offset of name status byte */
+#define NS_LOSS        0x01    /* Out of 8.3 format */
+#define NS_LFN        0x02    /* Force to create LFN entry */
+#define NS_LAST        0x04    /* Last segment */
+#define NS_BODY        0x08    /* Lower case flag (body) */
+#define NS_EXT        0x10    /* Lower case flag (ext) */
+#define NS_DOT        0x20    /* Dot entry */
+
+
+
+/*------------------------------------------------------------*/
+/* Work area                                                  */
+
+#if !_DRIVES
+#error Number of drives must not be 0.
+#endif
+static
+WORD Fsid;                /* File system mount ID */
+static
+FATFS *FatFs[_DRIVES];    /* Pointer to the file system objects (logical drives) */
+
+#if _FS_RPATH
+static
+BYTE Drive;                /* Current drive */
+#endif
+
+
+#if _USE_LFN == 0            /* No LFN */
+#define    DEF_NAMEBUF            BYTE sfn[12]
+#define INIT_BUF(dobj)        (dobj).fn = sfn
+#define    FREE_BUF()
+
+#elif _USE_LFN == 1            /* LFN with static LFN working buffer */
+static WCHAR LfnBuf[_MAX_LFN + 1];
+#define    DEF_NAMEBUF            BYTE sfn[12]
+#define INIT_BUF(dobj)        { (dobj).fn = sfn; (dobj).lfn = LfnBuf; }
+#define    FREE_BUF()
+
+#elif _USE_LFN == 2         /* LFN with dynamic LFN working buffer on the stack */
+#define    DEF_NAMEBUF            BYTE sfn[12]; WCHAR lbuf[_MAX_LFN + 1]
+#define INIT_BUF(dobj)        { (dobj).fn = sfn; (dobj).lfn = lbuf; }
+#define    FREE_BUF()
+
+#elif _USE_LFN == 3         /* LFN with dynamic LFN working buffer on the heap */
+#define    DEF_NAMEBUF            BYTE sfn[12]; WCHAR *lfn
+#define INIT_BUF(dobj)        { lfn = ff_memalloc((_MAX_LFN + 1) * 2); \
+                              if (!lfn) LEAVE_FF((dobj).fs, FR_NOT_ENOUGH_CORE); \
+                              (dobj).lfn = lfn;    (dobj).fn = sfn; }
+#define    FREE_BUF()            ff_memfree(lfn)
+
+#else
+#error Wrong LFN configuration.
+#endif
+
+
+
+
+/*--------------------------------------------------------------------------
+
+   Module Private Functions
+
+---------------------------------------------------------------------------*/
+
+
+/*-----------------------------------------------------------------------*/
+/* String functions                                                      */
+/*-----------------------------------------------------------------------*/
+
+/* Copy memory to memory */
+static
+void mem_cpy (void* dst, const void* src, int cnt) {
+    BYTE *d = (BYTE*)dst;
+    const BYTE *s = (const BYTE*)src;
+
+#if _WORD_ACCESS == 1
+    while (cnt >= sizeof(int)) {
+        *(int*)d = *(int*)s;
+        d += sizeof(int); s += sizeof(int);
+        cnt -= sizeof(int);
+    }
+#endif
+    while (cnt--)
+        *d++ = *s++;
+}
+
+/* Fill memory */
+static
+void mem_set (void* dst, int val, int cnt) {
+    BYTE *d = (BYTE*)dst;
+
+    while (cnt--)
+        *d++ = (BYTE)val;
+}
+
+/* Compare memory to memory */
+static
+int mem_cmp (const void* dst, const void* src, int cnt) {
+    const BYTE *d = (const BYTE *)dst, *s = (const BYTE *)src;
+    int r = 0;
+
+    while (cnt-- && (r = *d++ - *s++) == 0) ;
+    return r;
+}
+
+/* Check if chr is contained in the string */
+static
+int chk_chr (const char* str, int chr) {
+    while (*str && *str != chr) str++;
+    return *str;
+}
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Request/Release grant to access the volume                            */
+/*-----------------------------------------------------------------------*/
+#if _FS_REENTRANT
+
+static
+int lock_fs (
+    FATFS *fs        /* File system object */
+)
+{
+    return ff_req_grant(fs->sobj);
+}
+
+
+static
+void unlock_fs (
+    FATFS *fs,        /* File system object */
+    FRESULT res        /* Result code to be returned */
+)
+{
+    if (res != FR_NOT_ENABLED &&
+        res != FR_INVALID_DRIVE &&
+        res != FR_INVALID_OBJECT &&
+        res != FR_TIMEOUT) {
+        ff_rel_grant(fs->sobj);
+    }
+}
+#endif
+
+
+
+/*-----------------------------------------------------------------------*/
+/* File shareing control functions                                       */
+/*-----------------------------------------------------------------------*/
+#if _FS_SHARE
+
+static
+FRESULT chk_lock (    /* Check if the file can be accessed */
+    FAT_DIR* dj,        /* Directory object pointing the file to be checked */
+    int acc            /* Desired access (0:Read, 1:Write, 2:Delete/Rename) */
+)
+{
+    UINT i, be;
+
+    /* Search file semaphore table */
+    for (i = be = 0; i < _FS_SHARE; i++) {
+        if (dj->fs->flsem[i].ctr) {    /* Existing entry */
+            if (dj->fs->flsem[i].clu == dj->sclust &&     /* The file is found (identified with its location) */
+                dj->fs->flsem[i].idx == dj->index) break;
+        } else {                    /* Blank entry */
+            be++;
+        }
+    }
+    if (i == _FS_SHARE)    /* The file has not been opened */
+        return (be || acc != 2) ? FR_OK : FR_TOO_MANY_OPEN_FILES;    /* Is there a blank entry for new file? */
+
+    /* The file has been opened. Reject any open against writing file and all write mode open */
+    return (acc || dj->fs->flsem[i].ctr == 0x100) ? FR_LOCKED : FR_OK;
+}
+
+
+static
+int enq_lock (    /* Check if an entry is available for a new file */
+    FATFS* fs    /* File system object */
+)
+{
+    UINT i;
+
+    for (i = 0; i < _FS_SHARE && fs->flsem[i].ctr; i++) ;
+    return (i == _FS_SHARE) ? 0 : 1;
+}
+
+
+static
+UINT inc_lock (    /* Increment file open counter and returns its index (0:int error) */
+    FAT_DIR* dj,    /* Directory object pointing the file to register or increment */
+    int acc        /* Desired access mode (0:Read, !0:Write) */
+)
+{
+    UINT i;
+
+
+    for (i = 0; i < _FS_SHARE; i++) {    /* Find the file */
+        if (dj->fs->flsem[i].ctr &&
+            dj->fs->flsem[i].clu == dj->sclust &&
+            dj->fs->flsem[i].idx == dj->index) break;
+    }
+
+    if (i == _FS_SHARE) {                /* Not opened. Register it as new. */
+        for (i = 0; i < _FS_SHARE && dj->fs->flsem[i].ctr; i++) ;
+        if (i == _FS_SHARE) return 0;    /* No space to register (int err) */
+        dj->fs->flsem[i].clu = dj->sclust;
+        dj->fs->flsem[i].idx = dj->index;
+    }
+
+    if (acc && dj->fs->flsem[i].ctr) return 0;    /* Access violation (int err) */
+
+    dj->fs->flsem[i].ctr = acc ? 0x100 : dj->fs->flsem[i].ctr + 1;    /* Set semaphore value */
+
+    return i + 1;
+}
+
+
+static
+FRESULT dec_lock (    /* Decrement file open counter */
+    FATFS* fs,        /* File system object */
+    UINT i            /* Semaphore index */
+)
+{
+    WORD n;
+    FRESULT res;
+
+
+    if (--i < _FS_SHARE) {
+        n = fs->flsem[i].ctr;
+        if (n >= 0x100) n = 0;
+        if (n) n--;
+        fs->flsem[i].ctr = n;
+        res = FR_OK;
+    } else {
+        res = FR_INT_ERR;
+    }
+    return res;
+}
+
+#endif
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Change window offset                                                  */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT move_window (
+    FATFS *fs,        /* File system object */
+    DWORD sector    /* Sector number to make appearance in the fs->win[] */
+)                    /* Move to zero only writes back dirty window */
+{
+    DWORD wsect;
+
+
+    wsect = fs->winsect;
+    if (wsect != sector) {    /* Changed current window */
+#if !_FS_READONLY
+        if (fs->wflag) {    /* Write back dirty window if needed */
+            if (disk_write(fs->drv, fs->win, wsect, 1) != RES_OK)
+                return FR_DISK_ERR;
+            fs->wflag = 0;
+            if (wsect < (fs->fatbase + fs->fsize)) {    /* In FAT area */
+                BYTE nf;
+                for (nf = fs->n_fats; nf > 1; nf--) {    /* Reflect the change to all FAT copies */
+                    wsect += fs->fsize;
+                    disk_write(fs->drv, fs->win, wsect, 1);
+                }
+            }
+        }
+#endif
+        if (sector) {
+            if (disk_read(fs->drv, fs->win, sector, 1) != RES_OK)
+                return FR_DISK_ERR;
+            fs->winsect = sector;
+        }
+    }
+
+    return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Clean-up cached data                                                  */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+static
+FRESULT sync (    /* FR_OK: successful, FR_DISK_ERR: failed */
+    FATFS *fs    /* File system object */
+)
+{
+    FRESULT res;
+
+
+    res = move_window(fs, 0);
+    if (res == FR_OK) {
+        /* Update FSInfo sector if needed */
+        if (fs->fs_type == FS_FAT32 && fs->fsi_flag) {
+            fs->winsect = 0;
+            mem_set(fs->win, 0, 512);
+            ST_WORD(fs->win+BS_55AA, 0xAA55);
+            ST_DWORD(fs->win+FSI_LeadSig, 0x41615252);
+            ST_DWORD(fs->win+FSI_StrucSig, 0x61417272);
+            ST_DWORD(fs->win+FSI_Free_Count, fs->free_clust);
+            ST_DWORD(fs->win+FSI_Nxt_Free, fs->last_clust);
+            disk_write(fs->drv, fs->win, fs->fsi_sector, 1);
+            fs->fsi_flag = 0;
+        }
+        /* Make sure that no pending write process in the physical drive */
+        if (disk_ioctl(fs->drv, CTRL_SYNC, (void*)0) != RES_OK)
+            res = FR_DISK_ERR;
+    }
+
+    return res;
+}
+#endif
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT access - Read value of a FAT entry                                */
+/*-----------------------------------------------------------------------*/
+
+
+DWORD get_fat (    /* 0xFFFFFFFF:Disk error, 1:Internal error, Else:Cluster status */
+    FATFS *fs,    /* File system object */
+    DWORD clst    /* Cluster# to get the link information */
+)
+{
+    UINT wc, bc;
+    BYTE *p;
+
+
+    if (clst < 2 || clst >= fs->n_fatent)    /* Chack range */
+        return 1;
+
+    switch (fs->fs_type) {
+    case FS_FAT12 :
+        bc = (UINT)clst; bc += bc / 2;
+        if (move_window(fs, fs->fatbase + (bc / SS(fs)))) break;
+        wc = fs->win[bc % SS(fs)]; bc++;
+        if (move_window(fs, fs->fatbase + (bc / SS(fs)))) break;
+        wc |= fs->win[bc % SS(fs)] << 8;
+        return (clst & 1) ? (wc >> 4) : (wc & 0xFFF);
+
+    case FS_FAT16 :
+        if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 2)))) break;
+        p = &fs->win[clst * 2 % SS(fs)];
+        return LD_WORD(p);
+
+    case FS_FAT32 :
+        if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 4)))) break;
+        p = &fs->win[clst * 4 % SS(fs)];
+        return LD_DWORD(p) & 0x0FFFFFFF;
+    }
+
+    return 0xFFFFFFFF;    /* An error occurred at the disk I/O layer */
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT access - Change value of a FAT entry                              */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+
+FRESULT put_fat (
+    FATFS *fs,    /* File system object */
+    DWORD clst,    /* Cluster# to be changed in range of 2 to fs->n_fatent - 1 */
+    DWORD val    /* New value to mark the cluster */
+)
+{
+    UINT bc;
+    BYTE *p;
+    FRESULT res;
+
+
+    if (clst < 2 || clst >= fs->n_fatent) {    /* Check range */
+        res = FR_INT_ERR;
+
+    } else {
+        switch (fs->fs_type) {
+        case FS_FAT12 :
+            bc = clst; bc += bc / 2;
+            res = move_window(fs, fs->fatbase + (bc / SS(fs)));
+            if (res != FR_OK) break;
+            p = &fs->win[bc % SS(fs)];
+            *p = (clst & 1) ? ((*p & 0x0F) | ((BYTE)val << 4)) : (BYTE)val;
+            bc++;
+            fs->wflag = 1;
+            res = move_window(fs, fs->fatbase + (bc / SS(fs)));
+            if (res != FR_OK) break;
+            p = &fs->win[bc % SS(fs)];
+            *p = (clst & 1) ? (BYTE)(val >> 4) : ((*p & 0xF0) | ((BYTE)(val >> 8) & 0x0F));
+            break;
+
+        case FS_FAT16 :
+            res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 2)));
+            if (res != FR_OK) break;
+            p = &fs->win[clst * 2 % SS(fs)];
+            ST_WORD(p, (WORD)val);
+            break;
+
+        case FS_FAT32 :
+            res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 4)));
+            if (res != FR_OK) break;
+            p = &fs->win[clst * 4 % SS(fs)];
+            val |= LD_DWORD(p) & 0xF0000000;
+            ST_DWORD(p, val);
+            break;
+
+        default :
+            res = FR_INT_ERR;
+        }
+        fs->wflag = 1;
+    }
+
+    return res;
+}
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT handling - Remove a cluster chain                                 */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+static
+FRESULT remove_chain (
+    FATFS *fs,            /* File system object */
+    DWORD clst            /* Cluster# to remove a chain from */
+)
+{
+    FRESULT res;
+    DWORD nxt;
+
+
+    if (clst < 2 || clst >= fs->n_fatent) {    /* Check range */
+        res = FR_INT_ERR;
+
+    } else {
+        res = FR_OK;
+        while (clst < fs->n_fatent) {            /* Not a last link? */
+            nxt = get_fat(fs, clst);            /* Get cluster status */
+            if (nxt == 0) break;                /* Empty cluster? */
+            if (nxt == 1) { res = FR_INT_ERR; break; }    /* Internal error? */
+            if (nxt == 0xFFFFFFFF) { res = FR_DISK_ERR; break; }    /* Disk error? */
+            res = put_fat(fs, clst, 0);            /* Mark the cluster "empty" */
+            if (res != FR_OK) break;
+            if (fs->free_clust != 0xFFFFFFFF) {    /* Update FSInfo */
+                fs->free_clust++;
+                fs->fsi_flag = 1;
+            }
+            clst = nxt;    /* Next cluster */
+        }
+    }
+
+    return res;
+}
+#endif
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT handling - Stretch or Create a cluster chain                      */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+static
+DWORD create_chain (    /* 0:No free cluster, 1:Internal error, 0xFFFFFFFF:Disk error, >=2:New cluster# */
+    FATFS *fs,            /* File system object */
+    DWORD clst            /* Cluster# to stretch. 0 means create a new chain. */
+)
+{
+    DWORD cs, ncl, scl;
+
+
+    if (clst == 0) {        /* Create a new chain */
+        scl = fs->last_clust;            /* Get suggested start point */
+        if (!scl || scl >= fs->n_fatent) scl = 1;
+    }
+    else {                    /* Stretch the current chain */
+        cs = get_fat(fs, clst);            /* Check the cluster status */
+        if (cs < 2) return 1;            /* It is an invalid cluster */
+        if (cs < fs->n_fatent) return cs;    /* It is already followed by next cluster */
+        scl = clst;
+    }
+
+    ncl = scl;                /* Start cluster */
+    for (;;) {
+        ncl++;                            /* Next cluster */
+        if (ncl >= fs->n_fatent) {        /* Wrap around */
+            ncl = 2;
+            if (ncl > scl) return 0;    /* No free cluster */
+        }
+        cs = get_fat(fs, ncl);            /* Get the cluster status */
+        if (cs == 0) break;                /* Found a free cluster */
+        if (cs == 0xFFFFFFFF || cs == 1)/* An error occurred */
+            return cs;
+        if (ncl == scl) return 0;        /* No free cluster */
+    }
+
+    if (put_fat(fs, ncl, 0x0FFFFFFF))    /* Mark the new cluster "last link" */
+        return 0xFFFFFFFF;
+    if (clst != 0) {                    /* Link it to the previous one if needed */
+        if (put_fat(fs, clst, ncl))
+            return 0xFFFFFFFF;
+    }
+
+    fs->last_clust = ncl;                /* Update FSINFO */
+    if (fs->free_clust != 0xFFFFFFFF) {
+        fs->free_clust--;
+        fs->fsi_flag = 1;
+    }
+
+    return ncl;        /* Return new cluster number */
+}
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Get sector# from cluster#                                             */
+/*-----------------------------------------------------------------------*/
+
+
+DWORD clust2sect (    /* !=0: Sector number, 0: Failed - invalid cluster# */
+    FATFS *fs,        /* File system object */
+    DWORD clst        /* Cluster# to be converted */
+)
+{
+    clst -= 2;
+    if (clst >= (fs->n_fatent - 2)) return 0;        /* Invalid cluster# */
+    return clst * fs->csize + fs->database;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Set directory index                              */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_sdi (
+    FAT_DIR *dj,        /* Pointer to directory object */
+    WORD idx        /* Directory index number */
+)
+{
+    DWORD clst;
+    WORD ic;
+
+
+    dj->index = idx;
+    clst = dj->sclust;
+    if (clst == 1 || clst >= dj->fs->n_fatent)    /* Check start cluster range */
+        return FR_INT_ERR;
+    if (!clst && dj->fs->fs_type == FS_FAT32)    /* Replace cluster# 0 with root cluster# if in FAT32 */
+        clst = dj->fs->dirbase;
+
+    if (clst == 0) {    /* Static table */
+        dj->clust = clst;
+        if (idx >= dj->fs->n_rootdir)        /* Index is out of range */
+            return FR_INT_ERR;
+        dj->sect = dj->fs->dirbase + idx / (SS(dj->fs) / 32);    /* Sector# */
+    }
+    else {                /* Dynamic table */
+        ic = SS(dj->fs) / 32 * dj->fs->csize;    /* Entries per cluster */
+        while (idx >= ic) {    /* Follow cluster chain */
+            clst = get_fat(dj->fs, clst);                /* Get next cluster */
+            if (clst == 0xFFFFFFFF) return FR_DISK_ERR;    /* Disk error */
+            if (clst < 2 || clst >= dj->fs->n_fatent)    /* Reached to end of table or int error */
+                return FR_INT_ERR;
+            idx -= ic;
+        }
+        dj->clust = clst;
+        dj->sect = clust2sect(dj->fs, clst) + idx / (SS(dj->fs) / 32);    /* Sector# */
+    }
+
+    dj->dir = dj->fs->win + (idx % (SS(dj->fs) / 32)) * 32;    /* Ptr to the entry in the sector */
+
+    return FR_OK;    /* Seek succeeded */
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Move directory index next                        */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_next (    /* FR_OK:Succeeded, FR_NO_FILE:End of table, FR_DENIED:EOT and could not stretch */
+    FAT_DIR *dj,        /* Pointer to directory object */
+    int stretch        /* 0: Do not stretch table, 1: Stretch table if needed */
+)
+{
+    DWORD clst;
+    WORD i;
+
+
+    i = dj->index + 1;
+    if (!i || !dj->sect)    /* Report EOT when index has reached 65535 */
+        return FR_NO_FILE;
+
+    if (!(i % (SS(dj->fs) / 32))) {    /* Sector changed? */
+        dj->sect++;                    /* Next sector */
+
+        if (dj->clust == 0) {    /* Static table */
+            if (i >= dj->fs->n_rootdir)    /* Report EOT when end of table */
+                return FR_NO_FILE;
+        }
+        else {                    /* Dynamic table */
+            if (((i / (SS(dj->fs) / 32)) & (dj->fs->csize - 1)) == 0) {    /* Cluster changed? */
+                clst = get_fat(dj->fs, dj->clust);                /* Get next cluster */
+                if (clst <= 1) return FR_INT_ERR;
+                if (clst == 0xFFFFFFFF) return FR_DISK_ERR;
+                if (clst >= dj->fs->n_fatent) {                    /* When it reached end of dynamic table */
+#if !_FS_READONLY
+                    BYTE c;
+                    if (!stretch) return FR_NO_FILE;            /* When do not stretch, report EOT */
+                    clst = create_chain(dj->fs, dj->clust);        /* Stretch cluster chain */
+                    if (clst == 0) return FR_DENIED;            /* No free cluster */
+                    if (clst == 1) return FR_INT_ERR;
+                    if (clst == 0xFFFFFFFF) return FR_DISK_ERR;
+                    /* Clean-up stretched table */
+                    if (move_window(dj->fs, 0)) return FR_DISK_ERR;    /* Flush active window */
+                    mem_set(dj->fs->win, 0, SS(dj->fs));            /* Clear window buffer */
+                    dj->fs->winsect = clust2sect(dj->fs, clst);    /* Cluster start sector */
+                    for (c = 0; c < dj->fs->csize; c++) {        /* Fill the new cluster with 0 */
+                        dj->fs->wflag = 1;
+                        if (move_window(dj->fs, 0)) return FR_DISK_ERR;
+                        dj->fs->winsect++;
+                    }
+                    dj->fs->winsect -= c;                        /* Rewind window address */
+#else
+                    return FR_NO_FILE;            /* Report EOT */
+#endif
+                }
+                dj->clust = clst;                /* Initialize data for new cluster */
+                dj->sect = clust2sect(dj->fs, clst);
+            }
+        }
+    }
+
+    dj->index = i;
+    dj->dir = dj->fs->win + (i % (SS(dj->fs) / 32)) * 32;
+
+    return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* LFN handling - Test/Pick/Fit an LFN segment from/to directory entry   */
+/*-----------------------------------------------------------------------*/
+#if _USE_LFN
+static
+const BYTE LfnOfs[] = {1,3,5,7,9,14,16,18,20,22,24,28,30};    /* Offset of LFN chars in the directory entry */
+
+
+static
+int cmp_lfn (            /* 1:Matched, 0:Not matched */
+    WCHAR *lfnbuf,        /* Pointer to the LFN to be compared */
+    BYTE *dir            /* Pointer to the directory entry containing a part of LFN */
+)
+{
+    int i, s;
+    WCHAR wc, uc;
+
+
+    i = ((dir[LDIR_Ord] & 0xBF) - 1) * 13;    /* Get offset in the LFN buffer */
+    s = 0; wc = 1;
+    do {
+        uc = LD_WORD(dir+LfnOfs[s]);    /* Pick an LFN character from the entry */
+        if (wc) {    /* Last char has not been processed */
+            wc = ff_wtoupper(uc);        /* Convert it to upper case */
+            if (i >= _MAX_LFN || wc != ff_wtoupper(lfnbuf[i++]))    /* Compare it */
+                return 0;                /* Not matched */
+        } else {
+            if (uc != 0xFFFF) return 0;    /* Check filler */
+        }
+    } while (++s < 13);                /* Repeat until all chars in the entry are checked */
+
+    if ((dir[LDIR_Ord] & 0x40) && wc && lfnbuf[i])    /* Last segment matched but different length */
+        return 0;
+
+    return 1;                        /* The part of LFN matched */
+}
+
+
+
+static
+int pick_lfn (            /* 1:Succeeded, 0:Buffer overflow */
+    WCHAR *lfnbuf,        /* Pointer to the Unicode-LFN buffer */
+    BYTE *dir            /* Pointer to the directory entry */
+)
+{
+    int i, s;
+    WCHAR wc, uc;
+
+
+    i = ((dir[LDIR_Ord] & 0x3F) - 1) * 13;    /* Offset in the LFN buffer */
+
+    s = 0; wc = 1;
+    do {
+        uc = LD_WORD(dir+LfnOfs[s]);        /* Pick an LFN character from the entry */
+        if (wc) {    /* Last char has not been processed */
+            if (i >= _MAX_LFN) return 0;    /* Buffer overflow? */
+            lfnbuf[i++] = wc = uc;            /* Store it */
+        } else {
+            if (uc != 0xFFFF) return 0;        /* Check filler */
+        }
+    } while (++s < 13);                        /* Read all character in the entry */
+
+    if (dir[LDIR_Ord] & 0x40) {                /* Put terminator if it is the last LFN part */
+        if (i >= _MAX_LFN) return 0;        /* Buffer overflow? */
+        lfnbuf[i] = 0;
+    }
+
+    return 1;
+}
+
+
+#if !_FS_READONLY
+static
+void fit_lfn (
+    const WCHAR *lfnbuf,    /* Pointer to the LFN buffer */
+    BYTE *dir,                /* Pointer to the directory entry */
+    BYTE ord,                /* LFN order (1-20) */
+    BYTE sum                /* SFN sum */
+)
+{
+    int i, s;
+    WCHAR wc;
+
+
+    dir[LDIR_Chksum] = sum;            /* Set check sum */
+    dir[LDIR_Attr] = AM_LFN;        /* Set attribute. LFN entry */
+    dir[LDIR_Type] = 0;
+    ST_WORD(dir+LDIR_FstClusLO, 0);
+
+    i = (ord - 1) * 13;                /* Get offset in the LFN buffer */
+    s = wc = 0;
+    do {
+        if (wc != 0xFFFF) wc = lfnbuf[i++];    /* Get an effective char */
+        ST_WORD(dir+LfnOfs[s], wc);    /* Put it */
+        if (!wc) wc = 0xFFFF;        /* Padding chars following last char */
+    } while (++s < 13);
+    if (wc == 0xFFFF || !lfnbuf[i]) ord |= 0x40;    /* Bottom LFN part is the start of LFN sequence */
+    dir[LDIR_Ord] = ord;            /* Set the LFN order */
+}
+
+#endif
+#endif
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Create numbered name                                                  */
+/*-----------------------------------------------------------------------*/
+#if _USE_LFN
+void gen_numname (
+    BYTE *dst,            /* Pointer to generated SFN */
+    const BYTE *src,    /* Pointer to source SFN to be modified */
+    const WCHAR *lfn,    /* Pointer to LFN */
+    WORD seq            /* Sequence number */
+)
+{
+    BYTE ns[8], c;
+    int i, j;
+
+
+    mem_cpy(dst, src, 11);
+
+    if (seq > 5) {    /* On many collisions, generate a hash number instead of sequential number */
+        do seq = (seq >> 1) + (seq << 15) + (WORD)*lfn++; while (*lfn);
+    }
+
+    /* itoa */
+    i = 7;
+    do {
+        c = (seq % 16) + '0';
+        if (c > '9') c += 7;
+        ns[i--] = c;
+        seq /= 16;
+    } while (seq);
+    ns[i] = '~';
+
+    /* Append the number */
+    for (j = 0; j < i && dst[j] != ' '; j++) {
+        if (IsDBCS1(dst[j])) {
+            if (j == i - 1) break;
+            j++;
+        }
+    }
+    do {
+        dst[j++] = (i < 8) ? ns[i++] : ' ';
+    } while (j < 8);
+}
+#endif
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Calculate sum of an SFN                                               */
+/*-----------------------------------------------------------------------*/
+#if _USE_LFN
+static
+BYTE sum_sfn (
+    const BYTE *dir        /* Ptr to directory entry */
+)
+{
+    BYTE sum = 0;
+    int n = 11;
+
+    do sum = (sum >> 1) + (sum << 7) + *dir++; while (--n);
+    return sum;
+}
+#endif
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Find an object in the directory                  */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_find (
+    FAT_DIR *dj            /* Pointer to the directory object linked to the file name */
+)
+{
+    FRESULT res;
+    BYTE c, *dir;
+#if _USE_LFN
+    BYTE a, ord, sum;
+#endif
+
+    res = dir_sdi(dj, 0);            /* Rewind directory object */
+    if (res != FR_OK) return res;
+
+#if _USE_LFN
+    ord = sum = 0xFF;
+#endif
+    do {
+        res = move_window(dj->fs, dj->sect);
+        if (res != FR_OK) break;
+        dir = dj->dir;                    /* Ptr to the directory entry of current index */
+        c = dir[DIR_Name];
+        if (c == 0) { res = FR_NO_FILE; break; }    /* Reached to end of table */
+#if _USE_LFN    /* LFN configuration */
+        a = dir[DIR_Attr] & AM_MASK;
+        if (c == 0xE5 || ((a & AM_VOL) && a != AM_LFN)) {    /* An entry without valid data */
+            ord = 0xFF;
+        } else {
+            if (a == AM_LFN) {            /* An LFN entry is found */
+                if (dj->lfn) {
+                    if (c & 0x40) {        /* Is it start of LFN sequence? */
+                        sum = dir[LDIR_Chksum];
+                        c &= 0xBF; ord = c;    /* LFN start order */
+                        dj->lfn_idx = dj->index;
+                    }
+                    /* Check validity of the LFN entry and compare it with given name */
+                    ord = (c == ord && sum == dir[LDIR_Chksum] && cmp_lfn(dj->lfn, dir)) ? ord - 1 : 0xFF;
+                }
+            } else {                    /* An SFN entry is found */
+                if (!ord && sum == sum_sfn(dir)) break;    /* LFN matched? */
+                ord = 0xFF; dj->lfn_idx = 0xFFFF;    /* Reset LFN sequence */
+                if (!(dj->fn[NS] & NS_LOSS) && !mem_cmp(dir, dj->fn, 11)) break;    /* SFN matched? */
+            }
+        }
+#else        /* Non LFN configuration */
+        if (!(dir[DIR_Attr] & AM_VOL) && !mem_cmp(dir, dj->fn, 11)) /* Is it a valid entry? */
+            break;
+#endif
+        res = dir_next(dj, 0);        /* Next entry */
+    } while (res == FR_OK);
+
+    return res;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Read an object from the directory                                     */
+/*-----------------------------------------------------------------------*/
+#if _FS_MINIMIZE <= 1
+static
+FRESULT dir_read (
+    FAT_DIR *dj            /* Pointer to the directory object that pointing the entry to be read */
+)
+{
+    FRESULT res;
+    BYTE c, *dir;
+#if _USE_LFN
+    BYTE a, ord = 0xFF, sum = 0xFF;
+#endif
+
+    res = FR_NO_FILE;
+    while (dj->sect) {
+        res = move_window(dj->fs, dj->sect);
+        if (res != FR_OK) break;
+        dir = dj->dir;                    /* Ptr to the directory entry of current index */
+        c = dir[DIR_Name];
+        if (c == 0) { res = FR_NO_FILE; break; }    /* Reached to end of table */
+#if _USE_LFN    /* LFN configuration */
+        a = dir[DIR_Attr] & AM_MASK;
+        if (c == 0xE5 || (!_FS_RPATH && c == '.') || ((a & AM_VOL) && a != AM_LFN)) {    /* An entry without valid data */
+            ord = 0xFF;
+        } else {
+            if (a == AM_LFN) {            /* An LFN entry is found */
+                if (c & 0x40) {            /* Is it start of LFN sequence? */
+                    sum = dir[LDIR_Chksum];
+                    c &= 0xBF; ord = c;
+                    dj->lfn_idx = dj->index;
+                }
+                /* Check LFN validity and capture it */
+                ord = (c == ord && sum == dir[LDIR_Chksum] && pick_lfn(dj->lfn, dir)) ? ord - 1 : 0xFF;
+            } else {                    /* An SFN entry is found */
+                if (ord || sum != sum_sfn(dir))    /* Is there a valid LFN? */
+                    dj->lfn_idx = 0xFFFF;        /* It has no LFN. */
+                break;
+            }
+        }
+#else        /* Non LFN configuration */
+        if (c != 0xE5 && (_FS_RPATH || c != '.') && !(dir[DIR_Attr] & AM_VOL))    /* Is it a valid entry? */
+            break;
+#endif
+        res = dir_next(dj, 0);                /* Next entry */
+        if (res != FR_OK) break;
+    }
+
+    if (res != FR_OK) dj->sect = 0;
+
+    return res;
+}
+#endif
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Register an object to the directory                                   */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+static
+FRESULT dir_register (    /* FR_OK:Successful, FR_DENIED:No free entry or too many SFN collision, FR_DISK_ERR:Disk error */
+    FAT_DIR *dj                /* Target directory with object name to be created */
+)
+{
+    FRESULT res;
+    BYTE c, *dir;
+#if _USE_LFN    /* LFN configuration */
+    WORD n, ne, is;
+    BYTE sn[12], *fn, sum;
+    WCHAR *lfn;
+
+
+    fn = dj->fn; lfn = dj->lfn;
+    mem_cpy(sn, fn, 12);
+
+    if (_FS_RPATH && (sn[NS] & NS_DOT)) return FR_INVALID_NAME;    /* Cannot create dot entry */
+
+    if (sn[NS] & NS_LOSS) {            /* When LFN is out of 8.3 format, generate a numbered name */
+        fn[NS] = 0; dj->lfn = 0;            /* Find only SFN */
+        for (n = 1; n < 100; n++) {
+            gen_numname(fn, sn, lfn, n);    /* Generate a numbered name */
+            res = dir_find(dj);                /* Check if the name collides with existing SFN */
+            if (res != FR_OK) break;
+        }
+        if (n == 100) return FR_DENIED;        /* Abort if too many collisions */
+        if (res != FR_NO_FILE) return res;    /* Abort if the result is other than 'not collided' */
+        fn[NS] = sn[NS]; dj->lfn = lfn;
+    }
+
+    if (sn[NS] & NS_LFN) {            /* When LFN is to be created, reserve an SFN + LFN entries. */
+        for (ne = 0; lfn[ne]; ne++) ;
+        ne = (ne + 25) / 13;
+    } else {                        /* Otherwise reserve only an SFN entry. */
+        ne = 1;
+    }
+
+    /* Reserve contiguous entries */
+    res = dir_sdi(dj, 0);
+    if (res != FR_OK) return res;
+    n = is = 0;
+    do {
+        res = move_window(dj->fs, dj->sect);
+        if (res != FR_OK) break;
+        c = *dj->dir;                /* Check the entry status */
+        if (c == 0xE5 || c == 0) {    /* Is it a blank entry? */
+            if (n == 0) is = dj->index;    /* First index of the contiguous entry */
+            if (++n == ne) break;    /* A contiguous entry that required count is found */
+        } else {
+            n = 0;                    /* Not a blank entry. Restart to search */
+        }
+        res = dir_next(dj, 1);        /* Next entry with table stretch */
+    } while (res == FR_OK);
+
+    if (res == FR_OK && ne > 1) {    /* Initialize LFN entry if needed */
+        res = dir_sdi(dj, is);
+        if (res == FR_OK) {
+            sum = sum_sfn(dj->fn);    /* Sum of the SFN tied to the LFN */
+            ne--;
+            do {                    /* Store LFN entries in bottom first */
+                res = move_window(dj->fs, dj->sect);
+                if (res != FR_OK) break;
+                fit_lfn(dj->lfn, dj->dir, (BYTE)ne, sum);
+                dj->fs->wflag = 1;
+                res = dir_next(dj, 0);    /* Next entry */
+            } while (res == FR_OK && --ne);
+        }
+    }
+
+#else    /* Non LFN configuration */
+    res = dir_sdi(dj, 0);
+    if (res == FR_OK) {
+        do {    /* Find a blank entry for the SFN */
+            res = move_window(dj->fs, dj->sect);
+            if (res != FR_OK) break;
+            c = *dj->dir;
+            if (c == 0xE5 || c == 0) break;    /* Is it a blank entry? */
+            res = dir_next(dj, 1);            /* Next entry with table stretch */
+        } while (res == FR_OK);
+    }
+#endif
+
+    if (res == FR_OK) {        /* Initialize the SFN entry */
+        res = move_window(dj->fs, dj->sect);
+        if (res == FR_OK) {
+            dir = dj->dir;
+            mem_set(dir, 0, 32);        /* Clean the entry */
+            mem_cpy(dir, dj->fn, 11);    /* Put SFN */
+#if _USE_LFN
+            dir[DIR_NTres] = *(dj->fn+NS) & (NS_BODY | NS_EXT);    /* Put NT flag */
+#endif
+            dj->fs->wflag = 1;
+        }
+    }
+
+    return res;
+}
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Remove an object from the directory                                   */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY && !_FS_MINIMIZE
+static
+FRESULT dir_remove (    /* FR_OK: Successful, FR_DISK_ERR: A disk error */
+    FAT_DIR *dj                /* Directory object pointing the entry to be removed */
+)
+{
+    FRESULT res;
+#if _USE_LFN    /* LFN configuration */
+    WORD i;
+
+    i = dj->index;    /* SFN index */
+    res = dir_sdi(dj, (WORD)((dj->lfn_idx == 0xFFFF) ? i : dj->lfn_idx));    /* Goto the SFN or top of the LFN entries */
+    if (res == FR_OK) {
+        do {
+            res = move_window(dj->fs, dj->sect);
+            if (res != FR_OK) break;
+            *dj->dir = 0xE5;            /* Mark the entry "deleted" */
+            dj->fs->wflag = 1;
+            if (dj->index >= i) break;    /* When reached SFN, all entries of the object has been deleted. */
+            res = dir_next(dj, 0);        /* Next entry */
+        } while (res == FR_OK);
+        if (res == FR_NO_FILE) res = FR_INT_ERR;
+    }
+
+#else            /* Non LFN configuration */
+    res = dir_sdi(dj, dj->index);
+    if (res == FR_OK) {
+        res = move_window(dj->fs, dj->sect);
+        if (res == FR_OK) {
+            *dj->dir = 0xE5;            /* Mark the entry "deleted" */
+            dj->fs->wflag = 1;
+        }
+    }
+#endif
+
+    return res;
+}
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Pick a segment and create the object name in directory form           */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT create_name (
+    FAT_DIR *dj,            /* Pointer to the directory object */
+    const TCHAR **path    /* Pointer to pointer to the segment in the path string */
+)
+{
+#ifdef _EXCVT
+    static const BYTE excvt[] = _EXCVT;    /* Upper conversion table for extended chars */
+#endif
+
+#if _USE_LFN    /* LFN configuration */
+    BYTE b, cf;
+    WCHAR w, *lfn;
+    int i, ni, si, di;
+    const TCHAR *p;
+
+    /* Create LFN in Unicode */
+    si = di = 0;
+    p = *path;
+    lfn = dj->lfn;
+    for (;;) {
+        w = p[si++];                    /* Get a character */
+        if (w < ' ' || w == '/' || w == '\\') break;    /* Break on end of segment */
+        if (di >= _MAX_LFN)                /* Reject too long name */
+            return FR_INVALID_NAME;
+#if !_LFN_UNICODE
+        w &= 0xFF;
+        if (IsDBCS1(w)) {                /* If it is a DBC 1st byte */
+            b = p[si++];                /* Get 2nd byte */
+            if (!IsDBCS2(b))            /* Reject invalid code for DBC */
+                return FR_INVALID_NAME;
+            w = (w << 8) + b;
+        }
+        w = ff_convert(w, 1);            /* Convert OEM to Unicode */
+        if (!w) return FR_INVALID_NAME;    /* Reject invalid code */
+#endif
+        if (w < 0x80 && chk_chr("\"*:<>\?|\x7F", w)) /* Reject illegal chars for LFN */
+            return FR_INVALID_NAME;
+        lfn[di++] = w;                    /* Store the Unicode char */
+    }
+    *path = &p[si];                        /* Return pointer to the next segment */
+    cf = (w < ' ') ? NS_LAST : 0;        /* Set last segment flag if end of path */
+#if _FS_RPATH
+    if ((di == 1 && lfn[di - 1] == '.') || /* Is this a dot entry? */
+        (di == 2 && lfn[di - 1] == '.' && lfn[di - 2] == '.')) {
+        lfn[di] = 0;
+        for (i = 0; i < 11; i++)
+            dj->fn[i] = (i < di) ? '.' : ' ';
+        dj->fn[i] = cf | NS_DOT;        /* This is a dot entry */
+        return FR_OK;
+    }
+#endif
+    while (di) {                        /* Strip trailing spaces and dots */
+        w = lfn[di - 1];
+        if (w != ' ' && w != '.') break;
+        di--;
+    }
+    if (!di) return FR_INVALID_NAME;    /* Reject nul string */
+
+    lfn[di] = 0;                        /* LFN is created */
+
+    /* Create SFN in directory form */
+    mem_set(dj->fn, ' ', 11);
+    for (si = 0; lfn[si] == ' ' || lfn[si] == '.'; si++) ;    /* Strip leading spaces and dots */
+    if (si) cf |= NS_LOSS | NS_LFN;
+    while (di && lfn[di - 1] != '.') di--;    /* Find extension (di<=si: no extension) */
+
+    b = i = 0; ni = 8;
+    for (;;) {
+        w = lfn[si++];                    /* Get an LFN char */
+        if (!w) break;                    /* Break on end of the LFN */
+        if (w == ' ' || (w == '.' && si != di)) {    /* Remove spaces and dots */
+            cf |= NS_LOSS | NS_LFN; continue;
+        }
+
+        if (i >= ni || si == di) {        /* Extension or end of SFN */
+            if (ni == 11) {                /* Long extension */
+                cf |= NS_LOSS | NS_LFN; break;
+            }
+            if (si != di) cf |= NS_LOSS | NS_LFN;    /* Out of 8.3 format */
+            if (si > di) break;            /* No extension */
+            si = di; i = 8; ni = 11;    /* Enter extension section */
+            b <<= 2; continue;
+        }
+
+        if (w >= 0x80) {                /* Non ASCII char */
+#ifdef _EXCVT
+            w = ff_convert(w, 0);        /* Unicode -> OEM code */
+            if (w) w = excvt[w - 0x80];    /* Convert extended char to upper (SBCS) */
+#else
+            w = ff_convert(ff_wtoupper(w), 0);    /* Upper converted Unicode -> OEM code */
+#endif
+            cf |= NS_LFN;                /* Force create LFN entry */
+        }
+
+        if (_DF1S && w >= 0x100) {        /* Double byte char */
+            if (i >= ni - 1) {
+                cf |= NS_LOSS | NS_LFN; i = ni; continue;
+            }
+            dj->fn[i++] = (BYTE)(w >> 8);
+        } else {                        /* Single byte char */
+            if (!w || chk_chr("+,;=[]", w)) {        /* Replace illegal chars for SFN */
+                w = '_'; cf |= NS_LOSS | NS_LFN;    /* Lossy conversion */
+            } else {
+                if (IsUpper(w)) {        /* ASCII large capital */
+                    b |= 2;
+                } else {
+                    if (IsLower(w)) {    /* ASCII small capital */
+                        b |= 1; w -= 0x20;
+                    }
+                }
+            }
+        }
+        dj->fn[i++] = (BYTE)w;
+    }
+
+    if (dj->fn[0] == 0xE5) dj->fn[0] = 0x05;    /* If the first char collides with deleted mark, replace it with 0x05 */
+
+    if (ni == 8) b <<= 2;
+    if ((b & 0x0C) == 0x0C || (b & 0x03) == 0x03)    /* Create LFN entry when there are composite capitals */
+        cf |= NS_LFN;
+    if (!(cf & NS_LFN)) {                        /* When LFN is in 8.3 format without extended char, NT flags are created */
+        if ((b & 0x03) == 0x01) cf |= NS_EXT;    /* NT flag (Extension has only small capital) */
+        if ((b & 0x0C) == 0x04) cf |= NS_BODY;    /* NT flag (Filename has only small capital) */
+    }
+
+    dj->fn[NS] = cf;    /* SFN is created */
+
+    return FR_OK;
+
+
+#else    /* Non-LFN configuration */
+    BYTE b, c, d, *sfn;
+    int ni, si, i;
+    const char *p;
+
+    /* Create file name in directory form */
+    sfn = dj->fn;
+    mem_set(sfn, ' ', 11);
+    si = i = b = 0; ni = 8;
+    p = *path;
+#if _FS_RPATH
+    if (p[si] == '.') { /* Is this a dot entry? */
+        for (;;) {
+            c = (BYTE)p[si++];
+            if (c != '.' || si >= 3) break;
+            sfn[i++] = c;
+        }
+        if (c != '/' && c != '\\' && c > ' ') return FR_INVALID_NAME;
+        *path = &p[si];                                    /* Return pointer to the next segment */
+        sfn[NS] = (c <= ' ') ? NS_LAST | NS_DOT : NS_DOT;    /* Set last segment flag if end of path */
+        return FR_OK;
+    }
+#endif
+    for (;;) {
+        c = (BYTE)p[si++];
+        if (c <= ' ' || c == '/' || c == '\\') break;    /* Break on end of segment */
+        if (c == '.' || i >= ni) {
+            if (ni != 8 || c != '.') return FR_INVALID_NAME;
+            i = 8; ni = 11;
+            b <<= 2; continue;
+        }
+        if (c >= 0x80) {                /* Extended char */
+#ifdef _EXCVT
+            c = excvt[c - 0x80];        /* Convert extend char (SBCS) */
+#else
+            b |= 3;                        /* Eliminate NT flag if extended char is exist */
+#if !_DF1S    /* ASCII only cfg */
+            return FR_INVALID_NAME;
+#endif
+#endif
+        }
+        if (IsDBCS1(c)) {                /* DBC 1st byte? */
+            d = (BYTE)p[si++];            /* Get 2nd byte */
+            if (!IsDBCS2(d) || i >= ni - 1)    /* Reject invalid DBC */
+                return FR_INVALID_NAME;
+            sfn[i++] = c;
+            sfn[i++] = d;
+        } else {                        /* Single byte code */
+            if (chk_chr("\"*+,:<=>\?[]|\x7F", c))    /* Reject illegal chrs for SFN */
+                return FR_INVALID_NAME;
+            if (IsUpper(c)) {            /* ASCII large capital? */
+                b |= 2;
+            } else {
+                if (IsLower(c)) {        /* ASCII small capital? */
+                    b |= 1; c -= 0x20;
+                }
+            }
+            sfn[i++] = c;
+        }
+    }
+    *path = &p[si];                        /* Return pointer to the next segment */
+    c = (c <= ' ') ? NS_LAST : 0;        /* Set last segment flag if end of path */
+
+    if (!i) return FR_INVALID_NAME;        /* Reject nul string */
+    if (sfn[0] == 0xE5) sfn[0] = 0x05;    /* When first char collides with 0xE5, replace it with 0x05 */
+
+    if (ni == 8) b <<= 2;
+    if ((b & 0x03) == 0x01) c |= NS_EXT;    /* NT flag (Name extension has only small capital) */
+    if ((b & 0x0C) == 0x04) c |= NS_BODY;    /* NT flag (Name body has only small capital) */
+
+    sfn[NS] = c;        /* Store NT flag, File name is created */
+
+    return FR_OK;
+#endif
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Get file information from directory entry                             */
+/*-----------------------------------------------------------------------*/
+#if _FS_MINIMIZE <= 1
+static
+void get_fileinfo (        /* No return code */
+    FAT_DIR *dj,            /* Pointer to the directory object */
+    FILINFO *fno         /* Pointer to the file information to be filled */
+)
+{
+    int i;
+    BYTE nt, *dir;
+    TCHAR *p, c;
+
+
+    p = fno->fname;
+    if (dj->sect) {
+        dir = dj->dir;
+        nt = dir[DIR_NTres];        /* NT flag */
+        for (i = 0; i < 8; i++) {    /* Copy name body */
+            c = dir[i];
+            if (c == ' ') break;
+            if (c == 0x05) c = (TCHAR)0xE5;
+            if (_USE_LFN && (nt & NS_BODY) && IsUpper(c)) c += 0x20;
+#if _LFN_UNICODE
+            if (IsDBCS1(c) && i < 7 && IsDBCS2(dir[i + 1]))
+                c = (c << 8) | dir[++i];
+            c = ff_convert(c, 1);
+            if (!c) c = '?';
+#endif
+            *p++ = c;
+        }
+        if (dir[8] != ' ') {        /* Copy name extension */
+            *p++ = '.';
+            for (i = 8; i < 11; i++) {
+                c = dir[i];
+                if (c == ' ') break;
+                if (_USE_LFN && (nt & NS_EXT) && IsUpper(c)) c += 0x20;
+#if _LFN_UNICODE
+                if (IsDBCS1(c) && i < 10 && IsDBCS2(dir[i + 1]))
+                    c = (c << 8) | dir[++i];
+                c = ff_convert(c, 1);
+                if (!c) c = '?';
+#endif
+                *p++ = c;
+            }
+        }
+        fno->fattrib = dir[DIR_Attr];                /* Attribute */
+        fno->fsize = LD_DWORD(dir+DIR_FileSize);    /* Size */
+        fno->fdate = LD_WORD(dir+DIR_WrtDate);        /* Date */
+        fno->ftime = LD_WORD(dir+DIR_WrtTime);        /* Time */
+    }
+    *p = 0;
+
+#if _USE_LFN
+    if (fno->lfname) {
+        TCHAR *tp = fno->lfname;
+        WCHAR w, *lfn;
+
+        i = 0;
+        if (dj->sect && dj->lfn_idx != 0xFFFF) {/* Get LFN if available */
+            lfn = dj->lfn;
+            while ((w = *lfn++) != 0) {            /* Get an LFN char */
+#if !_LFN_UNICODE
+                w = ff_convert(w, 0);            /* Unicode -> OEM conversion */
+                if (!w) { i = 0; break; }        /* Could not convert, no LFN */
+                if (_DF1S && w >= 0x100)        /* Put 1st byte if it is a DBC */
+                    tp[i++] = (TCHAR)(w >> 8);
+#endif
+                if (i >= fno->lfsize - 1) { i = 0; break; }    /* Buffer overrun, no LFN */
+                tp[i++] = (TCHAR)w;
+            }
+        }
+        tp[i] = 0;    /* Terminator */
+    }
+#endif
+}
+#endif /* _FS_MINIMIZE <= 1 */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Follow a file path                                                    */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT follow_path (    /* FR_OK(0): successful, !=0: error code */
+    FAT_DIR *dj,            /* Directory object to return last directory and found object */
+    const TCHAR *path    /* Full-path string to find a file or directory */
+)
+{
+    FRESULT res;
+    BYTE *dir, ns;
+
+
+#if _FS_RPATH
+    if (*path == '/' || *path == '\\') { /* There is a heading separator */
+        path++;    dj->sclust = 0;        /* Strip it and start from the root dir */
+    } else {                            /* No heading separator */
+        dj->sclust = dj->fs->cdir;    /* Start from the current dir */
+    }
+#else
+    if (*path == '/' || *path == '\\')    /* Strip heading separator if exist */
+        path++;
+    dj->sclust = 0;                        /* Start from the root dir */
+#endif
+
+    if ((UINT)*path < ' ') {            /* Nul path means the start directory itself */
+        res = dir_sdi(dj, 0);
+        dj->dir = 0;
+
+    } else {                            /* Follow path */
+        for (;;) {
+            res = create_name(dj, &path);    /* Get a segment */
+            if (res != FR_OK) break;
+            res = dir_find(dj);                /* Find it */
+            ns = *(dj->fn+NS);
+            if (res != FR_OK) {                /* Failed to find the object */
+                if (res != FR_NO_FILE) break;    /* Abort if any hard error occured */
+                /* Object not found */
+                if (_FS_RPATH && (ns & NS_DOT)) {    /* If dot entry is not exit */
+                    dj->sclust = 0; dj->dir = 0;    /* It is the root dir */
+                    res = FR_OK;
+                    if (!(ns & NS_LAST)) continue;
+                } else {                            /* Could not find the object */
+                    if (!(ns & NS_LAST)) res = FR_NO_PATH;
+                }
+                break;
+            }
+            if (ns & NS_LAST) break;            /* Last segment match. Function completed. */
+            dir = dj->dir;                        /* There is next segment. Follow the sub directory */
+            if (!(dir[DIR_Attr] & AM_DIR)) {    /* Cannot follow because it is a file */
+                res = FR_NO_PATH; break;
+            }
+            dj->sclust = ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);
+        }
+    }
+
+    return res;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Load boot record and check if it is an FAT boot record                */
+/*-----------------------------------------------------------------------*/
+
+static
+BYTE check_fs (    /* 0:The FAT BR, 1:Valid BR but not an FAT, 2:Not a BR, 3:Disk error */
+    FATFS *fs,    /* File system object */
+    DWORD sect    /* Sector# (lba) to check if it is an FAT boot record or not */
+)
+{
+    if (disk_read(fs->drv, fs->win, sect, 1) != RES_OK)    /* Load boot record */
+        return 3;
+    if (LD_WORD(&fs->win[BS_55AA]) != 0xAA55)        /* Check record signature (always placed at offset 510 even if the sector size is >512) */
+        return 2;
+
+    if ((LD_DWORD(&fs->win[BS_FilSysType]) & 0xFFFFFF) == 0x544146)    /* Check "FAT" string */
+        return 0;
+    if ((LD_DWORD(&fs->win[BS_FilSysType32]) & 0xFFFFFF) == 0x544146)
+        return 0;
+
+    return 1;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Make sure that the file system is valid                               */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT chk_mounted (    /* FR_OK(0): successful, !=0: any error occurred */
+    const TCHAR **path,    /* Pointer to pointer to the path name (drive number) */
+    FATFS **rfs,        /* Pointer to pointer to the found file system object */
+    BYTE chk_wp            /* !=0: Check media write protection for write access */
+)
+{
+    BYTE fmt, b, *tbl;
+    UINT vol;
+    DSTATUS stat;
+    DWORD bsect, fasize, tsect, sysect, nclst, szbfat;
+    WORD nrsv;
+    const TCHAR *p = *path;
+    FATFS *fs;
+
+    /* Get logical drive number from the path name */
+    vol = p[0] - '0';                /* Is there a drive number? */
+    if (vol <= 9 && p[1] == ':') {    /* Found a drive number, get and strip it */
+        p += 2; *path = p;            /* Return pointer to the path name */
+    } else {                        /* No drive number is given */
+#if _FS_RPATH
+        vol = Drive;                /* Use current drive */
+#else
+        vol = 0;                    /* Use drive 0 */
+#endif
+    }
+
+    /* Check if the logical drive is valid or not */
+    if (vol >= _DRIVES)             /* Is the drive number valid? */
+        return FR_INVALID_DRIVE;
+    *rfs = fs = FatFs[vol];            /* Return pointer to the corresponding file system object */
+    if (!fs) return FR_NOT_ENABLED;    /* Is the file system object available? */
+
+    ENTER_FF(fs);                    /* Lock file system */
+
+    if (fs->fs_type) {                /* If the logical drive has been mounted */
+        stat = disk_status(fs->drv);
+        if (!(stat & STA_NOINIT)) {    /* and the physical drive is kept initialized (has not been changed), */
+#if !_FS_READONLY
+            if (chk_wp && (stat & STA_PROTECT))    /* Check write protection if needed */
+                return FR_WRITE_PROTECTED;
+#endif
+            return FR_OK;            /* The file system object is valid */
+        }
+    }
+
+    /* The logical drive must be mounted. Following code attempts to mount the volume (initialize the file system object) */
+
+    fs->fs_type = 0;                    /* Clear the file system object */
+    fs->drv = (BYTE)LD2PD(vol);            /* Bind the logical drive and a physical drive */
+    stat = disk_initialize(fs->drv);    /* Initialize low level disk I/O layer */
+    if (stat & STA_NOINIT)                /* Check if the drive is ready */
+        return FR_NOT_READY;
+#if _MAX_SS != 512                        /* Get disk sector size if needed */
+    if (disk_ioctl(fs->drv, GET_SECTOR_SIZE, &SS(fs)) != RES_OK || SS(fs) > _MAX_SS)
+        return FR_NO_FILESYSTEM;
+#endif
+#if !_FS_READONLY
+    if (chk_wp && (stat & STA_PROTECT))    /* Check disk write protection if needed */
+        return FR_WRITE_PROTECTED;
+#endif
+    /* Search FAT partition on the drive (Supports only generic partitionings, FDISK and SFD) */
+    fmt = check_fs(fs, bsect = 0);        /* Check sector 0 if it is a VBR */
+    if (fmt == 1) {                        /* Not an FAT-VBR, the disk may be partitioned */
+        /* Check the partition listed in top of the partition table */
+        tbl = &fs->win[MBR_Table + LD2PT(vol) * 16];    /* Partition table */
+        if (tbl[4]) {                                    /* Is the partition existing? */
+            bsect = LD_DWORD(&tbl[8]);                    /* Partition offset in LBA */
+            fmt = check_fs(fs, bsect);                    /* Check the partition */
+        }
+    }
+    if (fmt == 3) return FR_DISK_ERR;
+    if (fmt) return FR_NO_FILESYSTEM;                    /* No FAT volume is found */
+
+    /* Following code initializes the file system object */
+
+    if (LD_WORD(fs->win+BPB_BytsPerSec) != SS(fs))        /* (BPB_BytsPerSec must be equal to the physical sector size) */
+        return FR_NO_FILESYSTEM;
+
+    fasize = LD_WORD(fs->win+BPB_FATSz16);                /* Number of sectors per FAT */
+    if (!fasize) fasize = LD_DWORD(fs->win+BPB_FATSz32);
+    fs->fsize = fasize;
+
+    fs->n_fats = b = fs->win[BPB_NumFATs];                /* Number of FAT copies */
+    if (b != 1 && b != 2) return FR_NO_FILESYSTEM;        /* (Must be 1 or 2) */
+    fasize *= b;                                        /* Number of sectors for FAT area */
+
+    fs->csize = b = fs->win[BPB_SecPerClus];            /* Number of sectors per cluster */
+    if (!b || (b & (b - 1))) return FR_NO_FILESYSTEM;    /* (Must be 1,2,4...128) */
+
+    fs->n_rootdir = LD_WORD(fs->win+BPB_RootEntCnt);    /* Number of root directory entries */
+    if (fs->n_rootdir % (SS(fs) / 32)) return FR_NO_FILESYSTEM;    /* (BPB_RootEntCnt must be sector aligned) */
+
+    tsect = LD_WORD(fs->win+BPB_TotSec16);                /* Number of sectors on the volume */
+    if (!tsect) tsect = LD_DWORD(fs->win+BPB_TotSec32);
+
+    nrsv = LD_WORD(fs->win+BPB_RsvdSecCnt);                /* Number of reserved sectors */
+    if (!nrsv) return FR_NO_FILESYSTEM;                    /* (BPB_RsvdSecCnt must not be 0) */
+
+    /* Determine the FAT sub type */
+    sysect = nrsv + fasize + fs->n_rootdir / (SS(fs) / 32);    /* RSV+FAT+DIR */
+    if (tsect < sysect) return FR_NO_FILESYSTEM;        /* (Invalid volume size) */
+    nclst = (tsect - sysect) / fs->csize;                /* Number of clusters */
+    if (!nclst) return FR_NO_FILESYSTEM;                /* (Invalid volume size) */
+    fmt = FS_FAT12;
+    if (nclst >= MIN_FAT16) fmt = FS_FAT16;
+    if (nclst >= MIN_FAT32) fmt = FS_FAT32;
+
+    /* Boundaries and Limits */
+    fs->n_fatent = nclst + 2;                            /* Number of FAT entries */
+    fs->database = bsect + sysect;                        /* Data start sector */
+    fs->fatbase = bsect + nrsv;                         /* FAT start sector */
+    if (fmt == FS_FAT32) {
+        if (fs->n_rootdir) return FR_NO_FILESYSTEM;        /* (BPB_RootEntCnt must be 0) */
+        fs->dirbase = LD_DWORD(fs->win+BPB_RootClus);    /* Root directory start cluster */
+        szbfat = fs->n_fatent * 4;                        /* (Required FAT size) */
+    } else {
+        if (!fs->n_rootdir)    return FR_NO_FILESYSTEM;    /* (BPB_RootEntCnt must not be 0) */
+        fs->dirbase = fs->fatbase + fasize;                /* Root directory start sector */
+        szbfat = (fmt == FS_FAT16) ?                    /* (Required FAT size) */
+            fs->n_fatent * 2 : fs->n_fatent * 3 / 2 + (fs->n_fatent & 1);
+    }
+    if (fs->fsize < (szbfat + (SS(fs) - 1)) / SS(fs))    /* (FAT size must not be less than FAT sectors */
+        return FR_NO_FILESYSTEM;
+
+#if !_FS_READONLY
+    /* Initialize cluster allocation information */
+    fs->free_clust = 0xFFFFFFFF;
+    fs->last_clust = 0;
+
+    /* Get fsinfo if available */
+    if (fmt == FS_FAT32) {
+         fs->fsi_flag = 0;
+        fs->fsi_sector = bsect + LD_WORD(fs->win+BPB_FSInfo);
+        if (disk_read(fs->drv, fs->win, fs->fsi_sector, 1) == RES_OK &&
+            LD_WORD(fs->win+BS_55AA) == 0xAA55 &&
+            LD_DWORD(fs->win+FSI_LeadSig) == 0x41615252 &&
+            LD_DWORD(fs->win+FSI_StrucSig) == 0x61417272) {
+                fs->last_clust = LD_DWORD(fs->win+FSI_Nxt_Free);
+                fs->free_clust = LD_DWORD(fs->win+FSI_Free_Count);
+        }
+    }
+#endif
+    fs->fs_type = fmt;        /* FAT sub-type */
+    fs->id = ++Fsid;        /* File system mount ID */
+    fs->winsect = 0;        /* Invalidate sector cache */
+    fs->wflag = 0;
+#if _FS_RPATH
+    fs->cdir = 0;            /* Current directory (root dir) */
+#endif
+#if _FS_SHARE                /* Clear file lock semaphores */
+    for (vol = 0; vol < _FS_SHARE; vol++)
+        fs->flsem[vol].ctr = 0;
+#endif
+
+    return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Check if the file/dir object is valid or not                          */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT validate (    /* FR_OK(0): The object is valid, !=0: Invalid */
+    FATFS *fs,        /* Pointer to the file system object */
+    WORD id            /* Member id of the target object to be checked */
+)
+{
+    if (!fs || !fs->fs_type || fs->id != id)
+        return FR_INVALID_OBJECT;
+
+    ENTER_FF(fs);        /* Lock file system */
+
+    if (disk_status(fs->drv) & STA_NOINIT)
+        return FR_NOT_READY;
+
+    return FR_OK;
+}
+
+
+
+
+/*--------------------------------------------------------------------------
+
+   Public Functions
+
+--------------------------------------------------------------------------*/
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Mount/Unmount a Logical Drive                                         */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_mount (
+    BYTE vol,        /* Logical drive number to be mounted/unmounted */
+    FATFS *fs        /* Pointer to new file system object (NULL for unmount)*/
+)
+{
+    FATFS *rfs;
+
+
+    if (vol >= _DRIVES)                /* Check if the drive number is valid */
+        return FR_INVALID_DRIVE;
+    rfs = FatFs[vol];                /* Get current fs object */
+
+    if (rfs) {
+#if _FS_REENTRANT                    /* Discard sync object of the current volume */
+        if (!ff_del_syncobj(rfs->sobj)) return FR_INT_ERR;
+#endif
+        rfs->fs_type = 0;            /* Clear old fs object */
+    }
+
+    if (fs) {
+        fs->fs_type = 0;            /* Clear new fs object */
+#if _FS_REENTRANT                    /* Create sync object for the new volume */
+        if (!ff_cre_syncobj(vol, &fs->sobj)) return FR_INT_ERR;
+#endif
+    }
+    FatFs[vol] = fs;                /* Register new fs object */
+
+    return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Open or Create a File                                                 */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_open (
+    FAT_FIL *fp,            /* Pointer to the blank file object */
+    const TCHAR *path,    /* Pointer to the file name */
+    BYTE mode            /* Access mode and file open mode flags */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    BYTE *dir;
+    DEF_NAMEBUF;
+
+
+    fp->fs = 0;            /* Clear file object */
+
+#if !_FS_READONLY
+    mode &= FA_READ | FA_WRITE | FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW;
+    res = chk_mounted(&path, &dj.fs, (BYTE)(mode & ~FA_READ));
+#else
+    mode &= FA_READ;
+    res = chk_mounted(&path, &dj.fs, 0);
+#endif
+    INIT_BUF(dj);
+    if (res == FR_OK)
+        res = follow_path(&dj, path);    /* Follow the file path */
+    dir = dj.dir;
+
+#if !_FS_READONLY    /* R/W configuration */
+    if (res == FR_OK) {
+        if (!dir)    /* Current dir itself */
+            res = FR_INVALID_NAME;
+#if _FS_SHARE
+        else
+            res = chk_lock(&dj, (mode & ~FA_READ) ? 1 : 0);
+#endif
+    }
+    /* Create or Open a file */
+    if (mode & (FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW)) {
+        DWORD dw, cl;
+
+        if (res != FR_OK) {                /* No file, create new */
+            if (res == FR_NO_FILE)        /* There is no file to open, create a new entry */
+#if _FS_SHARE
+                res = enq_lock(dj.fs) ? dir_register(&dj) : FR_TOO_MANY_OPEN_FILES;
+#else
+                res = dir_register(&dj);
+#endif
+            mode |= FA_CREATE_ALWAYS;
+            dir = dj.dir;                /* New entry */
+        }
+        else {                            /* Any object is already existing */
+            if (mode & FA_CREATE_NEW) {            /* Cannot create new */
+                res = FR_EXIST;
+            } else {
+                if (dir[DIR_Attr] & (AM_RDO | AM_DIR))    /* Cannot overwrite it (R/O or DIR) */
+                    res = FR_DENIED;
+            }
+        }
+        if (res == FR_OK && (mode & FA_CREATE_ALWAYS)) {    /* Truncate it if overwrite mode */
+            dw = get_fattime();                        /* Created time */
+            ST_DWORD(dir+DIR_CrtTime, dw);
+            dir[DIR_Attr] = 0;                    /* Reset attribute */
+            ST_DWORD(dir+DIR_FileSize, 0);        /* size = 0 */
+            cl = ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);    /* Get start cluster */
+            ST_WORD(dir+DIR_FstClusHI, 0);        /* cluster = 0 */
+            ST_WORD(dir+DIR_FstClusLO, 0);
+            dj.fs->wflag = 1;
+            if (cl) {                            /* Remove the cluster chain if exist */
+                dw = dj.fs->winsect;
+                res = remove_chain(dj.fs, cl);
+                if (res == FR_OK) {
+                    dj.fs->last_clust = cl - 1;    /* Reuse the cluster hole */
+                    res = move_window(dj.fs, dw);
+                }
+            }
+        }
+    }
+    else {    /* Open an existing file */
+        if (res == FR_OK) {                        /* Follow succeeded */
+            if (dir[DIR_Attr] & AM_DIR) {        /* It is a directory */
+                res = FR_NO_FILE;
+            } else {
+                if ((mode & FA_WRITE) && (dir[DIR_Attr] & AM_RDO)) /* R/O violation */
+                    res = FR_DENIED;
+            }
+        }
+    }
+    if (res == FR_OK) {
+        if (mode & (FA_WRITE | FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW))
+            mode |= FA__WRITTEN;                /* Set file changed flag */
+        fp->dir_sect = dj.fs->winsect;            /* Pointer to the directory entry */
+        fp->dir_ptr = dir;
+#if _FS_SHARE
+        fp->lockid = inc_lock(&dj, (mode & ~FA_READ) ? 1 : 0);
+        if (!fp->lockid) res = FR_INT_ERR;
+#endif
+    }
+
+#else                /* R/O configuration */
+    if (res == FR_OK) {                    /* Follow succeeded */
+        if (!dir) {                        /* Current dir itself */
+            res = FR_INVALID_NAME;
+        } else {
+            if (dir[DIR_Attr] & AM_DIR)    /* It is a directory */
+                res = FR_NO_FILE;
+        }
+    }
+#endif
+    FREE_BUF();
+
+    if (res == FR_OK) {
+        fp->flag = mode;                    /* File access mode */
+        fp->org_clust =                        /* File start cluster */
+            ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);
+        fp->fsize = LD_DWORD(dir+DIR_FileSize);    /* File size */
+        fp->fptr = 0;                        /* File pointer */
+        fp->dsect = 0;
+#if _USE_FASTSEEK
+        fp->cltbl = 0;                        /* No cluster link map table */
+#endif
+        fp->fs = dj.fs; fp->id = dj.fs->id;    /* Validate file object */
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Read File                                                             */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_read (
+    FAT_FIL *fp,         /* Pointer to the file object */
+    void *buff,        /* Pointer to data buffer */
+    UINT btr,        /* Number of bytes to read */
+    UINT *br        /* Pointer to number of bytes read */
+)
+{
+    FRESULT res;
+    DWORD clst, sect, remain;
+    UINT rcnt, cc;
+    BYTE csect, *rbuff = (BYTE*)buff;
+
+
+    *br = 0;    /* Initialize byte counter */
+
+    res = validate(fp->fs, fp->id);                    /* Check validity of the object */
+    if (res != FR_OK) LEAVE_FF(fp->fs, res);
+    if (fp->flag & FA__ERROR)                        /* Check abort flag */
+        LEAVE_FF(fp->fs, FR_INT_ERR);
+    if (!(fp->flag & FA_READ))                         /* Check access mode */
+        LEAVE_FF(fp->fs, FR_DENIED);
+    remain = fp->fsize - fp->fptr;
+    if (btr > remain) btr = (UINT)remain;            /* Truncate btr by remaining bytes */
+
+    for ( ;  btr;                                    /* Repeat until all data transferred */
+        rbuff += rcnt, fp->fptr += rcnt, *br += rcnt, btr -= rcnt) {
+        if ((fp->fptr % SS(fp->fs)) == 0) {            /* On the sector boundary? */
+            csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1));    /* Sector offset in the cluster */
+            if (!csect) {                            /* On the cluster boundary? */
+                clst = (fp->fptr == 0) ?            /* On the top of the file? */
+                    fp->org_clust : get_fat(fp->fs, fp->curr_clust);
+                if (clst <= 1) ABORT(fp->fs, FR_INT_ERR);
+                if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                fp->curr_clust = clst;                /* Update current cluster */
+            }
+            sect = clust2sect(fp->fs, fp->curr_clust);    /* Get current sector */
+            if (!sect) ABORT(fp->fs, FR_INT_ERR);
+            sect += csect;
+            cc = btr / SS(fp->fs);                    /* When remaining bytes >= sector size, */
+            if (cc) {                                /* Read maximum contiguous sectors directly */
+                if (csect + cc > fp->fs->csize)        /* Clip at cluster boundary */
+                    cc = fp->fs->csize - csect;
+                if (disk_read(fp->fs->drv, rbuff, sect, (BYTE)cc) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+#if !_FS_READONLY && _FS_MINIMIZE <= 2                /* Replace one of the read sectors with cached data if it contains a dirty sector */
+#if _FS_TINY
+                if (fp->fs->wflag && fp->fs->winsect - sect < cc)
+                    mem_cpy(rbuff + ((fp->fs->winsect - sect) * SS(fp->fs)), fp->fs->win, SS(fp->fs));
+#else
+                if ((fp->flag & FA__DIRTY) && fp->dsect - sect < cc)
+                    mem_cpy(rbuff + ((fp->dsect - sect) * SS(fp->fs)), fp->buf, SS(fp->fs));
+#endif
+#endif
+                rcnt = SS(fp->fs) * cc;                /* Number of bytes transferred */
+                continue;
+            }
+#if !_FS_TINY
+#if !_FS_READONLY
+            if (fp->flag & FA__DIRTY) {            /* Write sector I/O buffer if needed */
+                if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+                fp->flag &= ~FA__DIRTY;
+            }
+#endif
+            if (fp->dsect != sect) {            /* Fill sector buffer with file data */
+                if (disk_read(fp->fs->drv, fp->buf, sect, 1) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+            }
+#endif
+            fp->dsect = sect;
+        }
+        rcnt = SS(fp->fs) - (fp->fptr % SS(fp->fs));    /* Get partial sector data from sector buffer */
+        if (rcnt > btr) rcnt = btr;
+#if _FS_TINY
+        if (move_window(fp->fs, fp->dsect))            /* Move sector window */
+            ABORT(fp->fs, FR_DISK_ERR);
+        mem_cpy(rbuff, &fp->fs->win[fp->fptr % SS(fp->fs)], rcnt);    /* Pick partial sector */
+#else
+        mem_cpy(rbuff, &fp->buf[fp->fptr % SS(fp->fs)], rcnt);    /* Pick partial sector */
+#endif
+    }
+
+    LEAVE_FF(fp->fs, FR_OK);
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Write File                                                            */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_write (
+    FAT_FIL *fp,            /* Pointer to the file object */
+    const void *buff,    /* Pointer to the data to be written */
+    UINT btw,            /* Number of bytes to write */
+    UINT *bw            /* Pointer to number of bytes written */
+)
+{
+    FRESULT res;
+    DWORD clst, sect;
+    UINT wcnt, cc;
+    const BYTE *wbuff = (const BYTE*)buff;
+    BYTE csect;
+
+
+    *bw = 0;    /* Initialize byte counter */
+
+    res = validate(fp->fs, fp->id);                    /* Check validity of the object */
+    if (res != FR_OK) LEAVE_FF(fp->fs, res);
+    if (fp->flag & FA__ERROR)                        /* Check abort flag */
+        LEAVE_FF(fp->fs, FR_INT_ERR);
+    if (!(fp->flag & FA_WRITE))                        /* Check access mode */
+        LEAVE_FF(fp->fs, FR_DENIED);
+    if (fp->fsize + btw < fp->fsize) btw = 0;        /* File size cannot reach 4GB */
+
+    for ( ;  btw;                                    /* Repeat until all data transferred */
+        wbuff += wcnt, fp->fptr += wcnt, *bw += wcnt, btw -= wcnt) {
+        if ((fp->fptr % SS(fp->fs)) == 0) {            /* On the sector boundary? */
+            csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1));    /* Sector offset in the cluster */
+            if (!csect) {                            /* On the cluster boundary? */
+                if (fp->fptr == 0) {                /* On the top of the file? */
+                    clst = fp->org_clust;            /* Follow from the origin */
+                    if (clst == 0)                    /* When there is no cluster chain, */
+                        fp->org_clust = clst = create_chain(fp->fs, 0);    /* Create a new cluster chain */
+                } else {                            /* Middle or end of the file */
+                    clst = create_chain(fp->fs, fp->curr_clust);            /* Follow or stretch cluster chain */
+                }
+                if (clst == 0) break;                /* Could not allocate a new cluster (disk full) */
+                if (clst == 1) ABORT(fp->fs, FR_INT_ERR);
+                if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                fp->curr_clust = clst;                /* Update current cluster */
+            }
+#if _FS_TINY
+            if (fp->fs->winsect == fp->dsect && move_window(fp->fs, 0))    /* Write back data buffer prior to following direct transfer */
+                ABORT(fp->fs, FR_DISK_ERR);
+#else
+            if (fp->flag & FA__DIRTY) {        /* Write back data buffer prior to following direct transfer */
+                if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+                fp->flag &= ~FA__DIRTY;
+            }
+#endif
+            sect = clust2sect(fp->fs, fp->curr_clust);    /* Get current sector */
+            if (!sect) ABORT(fp->fs, FR_INT_ERR);
+            sect += csect;
+            cc = btw / SS(fp->fs);                    /* When remaining bytes >= sector size, */
+            if (cc) {                                /* Write maximum contiguous sectors directly */
+                if (csect + cc > fp->fs->csize)        /* Clip at cluster boundary */
+                    cc = fp->fs->csize - csect;
+                if (disk_write(fp->fs->drv, wbuff, sect, (BYTE)cc) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+#if _FS_TINY
+                if (fp->fs->winsect - sect < cc) {    /* Refill sector cache if it gets dirty by the direct write */
+                    mem_cpy(fp->fs->win, wbuff + ((fp->fs->winsect - sect) * SS(fp->fs)), SS(fp->fs));
+                    fp->fs->wflag = 0;
+                }
+#else
+                if (fp->dsect - sect < cc) {        /* Refill sector cache if it gets dirty by the direct write */
+                    mem_cpy(fp->buf, wbuff + ((fp->dsect - sect) * SS(fp->fs)), SS(fp->fs));
+                    fp->flag &= ~FA__DIRTY;
+                }
+#endif
+                wcnt = SS(fp->fs) * cc;                /* Number of bytes transferred */
+                continue;
+            }
+#if _FS_TINY
+            if (fp->fptr >= fp->fsize) {            /* Avoid silly buffer filling at growing edge */
+                if (move_window(fp->fs, 0)) ABORT(fp->fs, FR_DISK_ERR);
+                fp->fs->winsect = sect;
+            }
+#else
+            if (fp->dsect != sect) {                /* Fill sector buffer with file data */
+                if (fp->fptr < fp->fsize &&
+                    disk_read(fp->fs->drv, fp->buf, sect, 1) != RES_OK)
+                        ABORT(fp->fs, FR_DISK_ERR);
+            }
+#endif
+            fp->dsect = sect;
+        }
+        wcnt = SS(fp->fs) - (fp->fptr % SS(fp->fs));    /* Put partial sector into file I/O buffer */
+        if (wcnt > btw) wcnt = btw;
+#if _FS_TINY
+        if (move_window(fp->fs, fp->dsect))            /* Move sector window */
+            ABORT(fp->fs, FR_DISK_ERR);
+        mem_cpy(&fp->fs->win[fp->fptr % SS(fp->fs)], wbuff, wcnt);    /* Fit partial sector */
+        fp->fs->wflag = 1;
+#else
+        mem_cpy(&fp->buf[fp->fptr % SS(fp->fs)], wbuff, wcnt);    /* Fit partial sector */
+        fp->flag |= FA__DIRTY;
+#endif
+    }
+
+    if (fp->fptr > fp->fsize) fp->fsize = fp->fptr;    /* Update file size if needed */
+    fp->flag |= FA__WRITTEN;                        /* Set file changed flag */
+
+    LEAVE_FF(fp->fs, FR_OK);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Synchronize the File Object                                           */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_sync (
+    FAT_FIL *fp        /* Pointer to the file object */
+)
+{
+    FRESULT res;
+    DWORD tim;
+    BYTE *dir;
+
+
+    res = validate(fp->fs, fp->id);        /* Check validity of the object */
+    if (res == FR_OK) {
+        if (fp->flag & FA__WRITTEN) {    /* Has the file been written? */
+#if !_FS_TINY    /* Write-back dirty buffer */
+            if (fp->flag & FA__DIRTY) {
+                if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK)
+                    LEAVE_FF(fp->fs, FR_DISK_ERR);
+                fp->flag &= ~FA__DIRTY;
+            }
+#endif
+            /* Update the directory entry */
+            res = move_window(fp->fs, fp->dir_sect);
+            if (res == FR_OK) {
+                dir = fp->dir_ptr;
+                dir[DIR_Attr] |= AM_ARC;                    /* Set archive bit */
+                ST_DWORD(dir+DIR_FileSize, fp->fsize);        /* Update file size */
+                ST_WORD(dir+DIR_FstClusLO, fp->org_clust);    /* Update start cluster */
+                ST_WORD(dir+DIR_FstClusHI, fp->org_clust >> 16);
+                tim = get_fattime();                        /* Update updated time */
+                ST_DWORD(dir+DIR_WrtTime, tim);
+                fp->flag &= ~FA__WRITTEN;
+                fp->fs->wflag = 1;
+                res = sync(fp->fs);
+            }
+        }
+    }
+
+    LEAVE_FF(fp->fs, res);
+}
+
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Close File                                                            */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_close (
+    FAT_FIL *fp        /* Pointer to the file object to be closed */
+)
+{
+    FRESULT res;
+
+#if _FS_READONLY
+    FATFS *fs = fp->fs;
+    res = validate(fs, fp->id);
+    if (res == FR_OK) fp->fs = 0;    /* Discard file object */
+    LEAVE_FF(fs, res);
+
+#else
+    res = f_sync(fp);        /* Flush cached data */
+#if _FS_SHARE
+    if (res == FR_OK) {        /* Decrement open counter */
+#if _FS_REENTRANT
+        res = validate(fp->fs, fp->id);
+        if (res == FR_OK) {
+            res = dec_lock(fp->fs, fp->lockid);    
+            unlock_fs(fp->fs, FR_OK);
+        }
+#else
+        res = dec_lock(fp->fs, fp->lockid);
+#endif
+    }
+#endif
+    if (res == FR_OK) fp->fs = 0;    /* Discard file object */
+    return res;
+#endif
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Change Current Drive/Directory                                        */
+/*-----------------------------------------------------------------------*/
+
+#if _FS_RPATH
+
+FRESULT f_chdrive (
+    BYTE drv        /* Drive number */
+)
+{
+    if (drv >= _DRIVES) return FR_INVALID_DRIVE;
+
+    Drive = drv;
+
+    return FR_OK;
+}
+
+
+
+
+FRESULT f_chdir (
+    const TCHAR *path    /* Pointer to the directory path */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    BYTE *dir;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 0);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);        /* Follow the path */
+        FREE_BUF();
+        if (res == FR_OK) {                    /* Follow completed */
+            dir = dj.dir;                    /* Pointer to the entry */
+            if (!dir) {
+                dj.fs->cdir = dj.sclust;    /* Start directory itself */
+            } else {
+                if (dir[DIR_Attr] & AM_DIR)    /* Reached to the directory */
+                    dj.fs->cdir = ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);
+                else
+                    res = FR_NO_PATH;        /* Reached but a file */
+            }
+        }
+        if (res == FR_NO_FILE) res = FR_NO_PATH;
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+#endif
+
+
+
+#if _FS_MINIMIZE <= 2
+/*-----------------------------------------------------------------------*/
+/* Seek File R/W Pointer                                                 */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_lseek (
+    FAT_FIL *fp,        /* Pointer to the file object */
+    DWORD ofs        /* File pointer from top of file */
+)
+{
+    FRESULT res;
+
+
+    res = validate(fp->fs, fp->id);        /* Check validity of the object */
+    if (res != FR_OK) LEAVE_FF(fp->fs, res);
+    if (fp->flag & FA__ERROR)            /* Check abort flag */
+        LEAVE_FF(fp->fs, FR_INT_ERR);
+
+#if _USE_FASTSEEK
+    if (fp->cltbl) {    /* Fast seek */
+        DWORD cl, pcl, ncl, tcl, dsc, tlen, *tbl = fp->cltbl;
+        BYTE csc;
+
+        tlen = *tbl++;
+        if (ofs == CREATE_LINKMAP) {    /* Create link map table */
+            cl = fp->org_clust;
+            if (cl) {
+                do {
+                    if (tlen < 4) {    /* Not enough table items */
+                        res = FR_NOT_ENOUGH_CORE; break;
+                    }
+                    tcl = cl; ncl = 0;
+                    do {        /* Get a fragment and store the top and length */
+                        pcl = cl; ncl++;
+                        cl = get_fat(fp->fs, cl);
+                        if (cl <= 1) ABORT(fp->fs, FR_INT_ERR);
+                        if (cl == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                    } while (cl == pcl + 1);
+                    *tbl++ = ncl; *tbl++ = tcl;
+                    tlen -= 2;
+                } while (cl < fp->fs->n_fatent);
+            }
+            *tbl = 0;    /* Terminate table */
+
+        } else {                        /* Fast seek */
+            if (ofs > fp->fsize)        /* Clip offset at the file size */
+                ofs = fp->fsize;
+            fp->fptr = ofs;                /* Set file pointer */
+            if (ofs) {
+                dsc = (ofs - 1) / SS(fp->fs);
+                cl = dsc / fp->fs->csize;
+                for (;;) {
+                    ncl = *tbl++;
+                    if (!ncl) ABORT(fp->fs, FR_INT_ERR);
+                    if (cl < ncl) break;
+                    cl -= ncl; tbl++;
+                }
+                fp->curr_clust = cl + *tbl;
+                csc = (BYTE)(dsc & (fp->fs->csize - 1));
+                dsc = clust2sect(fp->fs, fp->curr_clust);
+                if (!dsc) ABORT(fp->fs, FR_INT_ERR);
+                dsc += csc;
+                if (fp->fptr % SS(fp->fs) && dsc != fp->dsect) {
+#if !_FS_TINY
+#if !_FS_READONLY
+                    if (fp->flag & FA__DIRTY) {        /* Flush dirty buffer if needed */
+                        if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK)
+                            ABORT(fp->fs, FR_DISK_ERR);
+                        fp->flag &= ~FA__DIRTY;
+                    }
+#endif
+                    if (disk_read(fp->fs->drv, fp->buf, dsc, 1) != RES_OK)
+                        ABORT(fp->fs, FR_DISK_ERR);
+#endif
+                    fp->dsect = dsc;
+                }
+            }
+        }
+    } else
+#endif
+
+    /* Normal Seek */
+    {
+        DWORD clst, bcs, nsect, ifptr;
+
+        if (ofs > fp->fsize                    /* In read-only mode, clip offset with the file size */
+#if !_FS_READONLY
+             && !(fp->flag & FA_WRITE)
+#endif
+            ) ofs = fp->fsize;
+
+        ifptr = fp->fptr;
+        fp->fptr = nsect = 0;
+        if (ofs) {
+            bcs = (DWORD)fp->fs->csize * SS(fp->fs);    /* Cluster size (byte) */
+            if (ifptr > 0 &&
+                (ofs - 1) / bcs >= (ifptr - 1) / bcs) {    /* When seek to same or following cluster, */
+                fp->fptr = (ifptr - 1) & ~(bcs - 1);    /* start from the current cluster */
+                ofs -= fp->fptr;
+                clst = fp->curr_clust;
+            } else {                                    /* When seek to back cluster, */
+                clst = fp->org_clust;                    /* start from the first cluster */
+#if !_FS_READONLY
+                if (clst == 0) {                        /* If no cluster chain, create a new chain */
+                    clst = create_chain(fp->fs, 0);
+                    if (clst == 1) ABORT(fp->fs, FR_INT_ERR);
+                    if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                    fp->org_clust = clst;
+                }
+#endif
+                fp->curr_clust = clst;
+            }
+            if (clst != 0) {
+                while (ofs > bcs) {                        /* Cluster following loop */
+#if !_FS_READONLY
+                    if (fp->flag & FA_WRITE) {            /* Check if in write mode or not */
+                        clst = create_chain(fp->fs, clst);    /* Force stretch if in write mode */
+                        if (clst == 0) {                /* When disk gets full, clip file size */
+                            ofs = bcs; break;
+                        }
+                    } else
+#endif
+                        clst = get_fat(fp->fs, clst);    /* Follow cluster chain if not in write mode */
+                    if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                    if (clst <= 1 || clst >= fp->fs->n_fatent) ABORT(fp->fs, FR_INT_ERR);
+                    fp->curr_clust = clst;
+                    fp->fptr += bcs;
+                    ofs -= bcs;
+                }
+                fp->fptr += ofs;
+                if (ofs % SS(fp->fs)) {
+                    nsect = clust2sect(fp->fs, clst);    /* Current sector */
+                    if (!nsect) ABORT(fp->fs, FR_INT_ERR);
+                    nsect += ofs / SS(fp->fs);
+                }
+            }
+        }
+        if (fp->fptr % SS(fp->fs) && nsect != fp->dsect) {
+#if !_FS_TINY
+#if !_FS_READONLY
+            if (fp->flag & FA__DIRTY) {            /* Flush dirty buffer if needed */
+                if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK)
+                    ABORT(fp->fs, FR_DISK_ERR);
+                fp->flag &= ~FA__DIRTY;
+            }
+#endif
+            if (disk_read(fp->fs->drv, fp->buf, nsect, 1) != RES_OK)
+                ABORT(fp->fs, FR_DISK_ERR);
+#endif
+            fp->dsect = nsect;
+        }
+#if !_FS_READONLY
+        if (fp->fptr > fp->fsize) {            /* Set changed flag if the file size is extended */
+            fp->fsize = fp->fptr;
+            fp->flag |= FA__WRITTEN;
+        }
+#endif
+    }
+
+    LEAVE_FF(fp->fs, res);
+}
+
+
+
+#if _FS_MINIMIZE <= 1
+/*-----------------------------------------------------------------------*/
+/* Create a Directroy Object                                             */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_opendir (
+    FAT_DIR *dj,            /* Pointer to directory object to create */
+    const TCHAR *path    /* Pointer to the directory path */
+)
+{
+    FRESULT res;
+    BYTE *dir;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj->fs, 0);
+    if (res == FR_OK) {
+        INIT_BUF(*dj);
+        res = follow_path(dj, path);            /* Follow the path to the directory */
+        FREE_BUF();
+        if (res == FR_OK) {                        /* Follow completed */
+            dir = dj->dir;
+            if (dir) {                            /* It is not the current dir */
+                if (dir[DIR_Attr] & AM_DIR) {    /* The object is a directory */
+                    dj->sclust = ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);
+                } else {                        /* The object is not a directory */
+                    res = FR_NO_PATH;
+                }
+            }
+            if (res == FR_OK) {
+                dj->id = dj->fs->id;
+                res = dir_sdi(dj, 0);            /* Rewind dir */
+            }
+        }
+        if (res == FR_NO_FILE) res = FR_NO_PATH;
+    }
+
+    LEAVE_FF(dj->fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Read Directory Entry in Sequense                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_readdir (
+    FAT_DIR *dj,            /* Pointer to the open directory object */
+    FILINFO *fno        /* Pointer to file information to return */
+)
+{
+    FRESULT res;
+    DEF_NAMEBUF;
+
+
+    res = validate(dj->fs, dj->id);            /* Check validity of the object */
+    if (res == FR_OK) {
+        if (!fno) {
+            res = dir_sdi(dj, 0);
+        } else {
+            INIT_BUF(*dj);
+            res = dir_read(dj);
+            if (res == FR_NO_FILE) {
+                dj->sect = 0;
+                res = FR_OK;
+            }
+            if (res == FR_OK) {                /* A valid entry is found */
+                get_fileinfo(dj, fno);        /* Get the object information */
+                res = dir_next(dj, 0);        /* Increment index for next */
+                if (res == FR_NO_FILE) {
+                    dj->sect = 0;
+                    res = FR_OK;
+                }
+            }
+            FREE_BUF();
+        }
+    }
+
+    LEAVE_FF(dj->fs, res);
+}
+
+
+
+#if _FS_MINIMIZE == 0
+/*-----------------------------------------------------------------------*/
+/* Get File Status                                                       */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_stat (
+    const TCHAR *path,    /* Pointer to the file path */
+    FILINFO *fno        /* Pointer to file information to return */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 0);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);    /* Follow the file path */
+        if (res == FR_OK) {                /* Follow completed */
+            if (dj.dir)        /* Found an object */
+                get_fileinfo(&dj, fno);
+            else            /* It is root dir */
+                res = FR_INVALID_NAME;
+        }
+        FREE_BUF();
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Get Number of Free Clusters                                           */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_getfree (
+    const TCHAR *path,    /* Pointer to the logical drive number (root dir) */
+    DWORD *nclst,        /* Pointer to the variable to return number of free clusters */
+    FATFS **fatfs        /* Pointer to pointer to corresponding file system object to return */
+)
+{
+    FRESULT res;
+    DWORD n, clst, sect, stat;
+    UINT i;
+    BYTE fat, *p;
+
+
+    /* Get drive number */
+    res = chk_mounted(&path, fatfs, 0);
+    if (res == FR_OK) {
+        /* If free_clust is valid, return it without full cluster scan */
+        if ((*fatfs)->free_clust <= (*fatfs)->n_fatent - 2) {
+            *nclst = (*fatfs)->free_clust;
+        } else {
+            /* Get number of free clusters */
+            fat = (*fatfs)->fs_type;
+            n = 0;
+            if (fat == FS_FAT12) {
+                clst = 2;
+                do {
+                    stat = get_fat(*fatfs, clst);
+                    if (stat == 0xFFFFFFFF) { res = FR_DISK_ERR; break; }
+                    if (stat == 1) { res = FR_INT_ERR; break; }
+                    if (stat == 0) n++;
+                } while (++clst < (*fatfs)->n_fatent);
+            } else {
+                clst = (*fatfs)->n_fatent;
+                sect = (*fatfs)->fatbase;
+                i = 0; p = 0;
+                do {
+                    if (!i) {
+                        res = move_window(*fatfs, sect++);
+                        if (res != FR_OK) break;
+                        p = (*fatfs)->win;
+                        i = SS(*fatfs);
+                    }
+                    if (fat == FS_FAT16) {
+                        if (LD_WORD(p) == 0) n++;
+                        p += 2; i -= 2;
+                    } else {
+                        if ((LD_DWORD(p) & 0x0FFFFFFF) == 0) n++;
+                        p += 4; i -= 4;
+                    }
+                } while (--clst);
+            }
+            (*fatfs)->free_clust = n;
+            if (fat == FS_FAT32) (*fatfs)->fsi_flag = 1;
+            *nclst = n;
+        }
+    }
+    LEAVE_FF(*fatfs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Truncate File                                                         */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_truncate (
+    FAT_FIL *fp        /* Pointer to the file object */
+)
+{
+    FRESULT res;
+    DWORD ncl;
+
+
+    res = validate(fp->fs, fp->id);        /* Check validity of the object */
+    if (res == FR_OK) {
+        if (fp->flag & FA__ERROR) {            /* Check abort flag */
+            res = FR_INT_ERR;
+        } else {
+            if (!(fp->flag & FA_WRITE))        /* Check access mode */
+                res = FR_DENIED;
+        }
+    }
+    if (res == FR_OK) {
+        if (fp->fsize > fp->fptr) {
+            fp->fsize = fp->fptr;    /* Set file size to current R/W point */
+            fp->flag |= FA__WRITTEN;
+            if (fp->fptr == 0) {    /* When set file size to zero, remove entire cluster chain */
+                res = remove_chain(fp->fs, fp->org_clust);
+                fp->org_clust = 0;
+            } else {                /* When truncate a part of the file, remove remaining clusters */
+                ncl = get_fat(fp->fs, fp->curr_clust);
+                res = FR_OK;
+                if (ncl == 0xFFFFFFFF) res = FR_DISK_ERR;
+                if (ncl == 1) res = FR_INT_ERR;
+                if (res == FR_OK && ncl < fp->fs->n_fatent) {
+                    res = put_fat(fp->fs, fp->curr_clust, 0x0FFFFFFF);
+                    if (res == FR_OK) res = remove_chain(fp->fs, ncl);
+                }
+            }
+        }
+        if (res != FR_OK) fp->flag |= FA__ERROR;
+    }
+
+    LEAVE_FF(fp->fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Delete a File or Directory                                            */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_unlink (
+    const TCHAR *path        /* Pointer to the file or directory path */
+)
+{
+    FRESULT res;
+    FAT_DIR dj, sdj;
+    BYTE *dir;
+    DWORD dclst;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 1);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);        /* Follow the file path */
+        if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT))
+            res = FR_INVALID_NAME;            /* Cannot remove dot entry */
+#if _FS_SHARE
+        if (res == FR_OK) res = chk_lock(&dj, 2);    /* Cannot remove open file */
+#endif
+        if (res == FR_OK) {                    /* The object is accessible */
+            dir = dj.dir;
+            if (!dir) {
+                res = FR_INVALID_NAME;        /* Cannot remove the start directory */
+            } else {
+                if (dir[DIR_Attr] & AM_RDO)
+                    res = FR_DENIED;        /* Cannot remove R/O object */
+            }
+            dclst = ((DWORD)LD_WORD(dir+DIR_FstClusHI) << 16) | LD_WORD(dir+DIR_FstClusLO);
+            if (res == FR_OK && (dir[DIR_Attr] & AM_DIR)) {    /* Is it a sub-dir? */
+                if (dclst < 2) {
+                    res = FR_INT_ERR;
+                } else {
+                    mem_cpy(&sdj, &dj, sizeof(FAT_DIR));    /* Check if the sub-dir is empty or not */
+                    sdj.sclust = dclst;
+                    res = dir_sdi(&sdj, 2);        /* Exclude dot entries */
+                    if (res == FR_OK) {
+                        res = dir_read(&sdj);
+                        if (res == FR_OK            /* Not empty dir */
+#if _FS_RPATH
+                        || dclst == sdj.fs->cdir    /* Current dir */
+#endif
+                        ) res = FR_DENIED;
+                        if (res == FR_NO_FILE) res = FR_OK;    /* Empty */
+                    }
+                }
+            }
+            if (res == FR_OK) {
+                res = dir_remove(&dj);        /* Remove the directory entry */
+                if (res == FR_OK) {
+                    if (dclst)                /* Remove the cluster chain if exist */
+                        res = remove_chain(dj.fs, dclst);
+                    if (res == FR_OK) res = sync(dj.fs);
+                }
+            }
+        }
+        FREE_BUF();
+    }
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Create a Directory                                                    */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_mkdir (
+    const TCHAR *path        /* Pointer to the directory path */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    BYTE *dir, n;
+    DWORD dsc, dcl, pcl, tim = get_fattime();
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 1);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);            /* Follow the file path */
+        if (res == FR_OK) res = FR_EXIST;        /* Any object with same name is already existing */
+        if (_FS_RPATH && res == FR_NO_FILE && (dj.fn[NS] & NS_DOT))
+            res = FR_INVALID_NAME;
+        if (res == FR_NO_FILE) {                /* Can create a new directory */
+            dcl = create_chain(dj.fs, 0);        /* Allocate a cluster for the new directory table */
+            res = FR_OK;
+            if (dcl == 0) res = FR_DENIED;        /* No space to allocate a new cluster */
+            if (dcl == 1) res = FR_INT_ERR;
+            if (dcl == 0xFFFFFFFF) res = FR_DISK_ERR;
+            if (res == FR_OK)                    /* Flush FAT */
+                res = move_window(dj.fs, 0);
+            if (res == FR_OK) {                    /* Initialize the new directory table */
+                dsc = clust2sect(dj.fs, dcl);
+                dir = dj.fs->win;
+                mem_set(dir, 0, SS(dj.fs));
+                mem_set(dir+DIR_Name, ' ', 8+3);    /* Create "." entry */
+                dir[DIR_Name] = '.';
+                dir[DIR_Attr] = AM_DIR;
+                ST_DWORD(dir+DIR_WrtTime, tim);
+                ST_WORD(dir+DIR_FstClusLO, dcl);
+                ST_WORD(dir+DIR_FstClusHI, dcl >> 16);
+                mem_cpy(dir+32, dir, 32);             /* Create ".." entry */
+                dir[33] = '.'; pcl = dj.sclust;
+                if (dj.fs->fs_type == FS_FAT32 && pcl == dj.fs->dirbase)
+                    pcl = 0;
+                ST_WORD(dir+32+DIR_FstClusLO, pcl);
+                ST_WORD(dir+32+DIR_FstClusHI, pcl >> 16);
+                for (n = dj.fs->csize; n; n--) {    /* Write dot entries and clear following sectors */
+                    dj.fs->winsect = dsc++;
+                    dj.fs->wflag = 1;
+                    res = move_window(dj.fs, 0);
+                    if (res != FR_OK) break;
+                    mem_set(dir, 0, SS(dj.fs));
+                }
+            }
+            if (res == FR_OK) res = dir_register(&dj);    /* Register the object to the directoy */
+            if (res != FR_OK) {
+                remove_chain(dj.fs, dcl);                /* Could not register, remove cluster chain */
+            } else {
+                dir = dj.dir;
+                dir[DIR_Attr] = AM_DIR;                    /* Attribute */
+                ST_DWORD(dir+DIR_WrtTime, tim);            /* Created time */
+                ST_WORD(dir+DIR_FstClusLO, dcl);        /* Table start cluster */
+                ST_WORD(dir+DIR_FstClusHI, dcl >> 16);
+                dj.fs->wflag = 1;
+                res = sync(dj.fs);
+            }
+        }
+        FREE_BUF();
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Change Attribute                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_chmod (
+    const TCHAR *path,    /* Pointer to the file path */
+    BYTE value,            /* Attribute bits */
+    BYTE mask            /* Attribute mask to change */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    BYTE *dir;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 1);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);        /* Follow the file path */
+        FREE_BUF();
+        if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT))
+            res = FR_INVALID_NAME;
+        if (res == FR_OK) {
+            dir = dj.dir;
+            if (!dir) {                        /* Is it a root directory? */
+                res = FR_INVALID_NAME;
+            } else {                        /* File or sub directory */
+                mask &= AM_RDO|AM_HID|AM_SYS|AM_ARC;    /* Valid attribute mask */
+                dir[DIR_Attr] = (value & mask) | (dir[DIR_Attr] & (BYTE)~mask);    /* Apply attribute change */
+                dj.fs->wflag = 1;
+                res = sync(dj.fs);
+            }
+        }
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Change Timestamp                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_utime (
+    const TCHAR *path,    /* Pointer to the file/directory name */
+    const FILINFO *fno    /* Pointer to the time stamp to be set */
+)
+{
+    FRESULT res;
+    FAT_DIR dj;
+    BYTE *dir;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path, &dj.fs, 1);
+    if (res == FR_OK) {
+        INIT_BUF(dj);
+        res = follow_path(&dj, path);    /* Follow the file path */
+        FREE_BUF();
+        if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT))
+            res = FR_INVALID_NAME;
+        if (res == FR_OK) {
+            dir = dj.dir;
+            if (!dir) {                    /* Root directory */
+                res = FR_INVALID_NAME;
+            } else {                    /* File or sub-directory */
+                ST_WORD(dir+DIR_WrtTime, fno->ftime);
+                ST_WORD(dir+DIR_WrtDate, fno->fdate);
+                dj.fs->wflag = 1;
+                res = sync(dj.fs);
+            }
+        }
+    }
+
+    LEAVE_FF(dj.fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Rename File/Directory                                                 */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_rename (
+    const TCHAR *path_old,    /* Pointer to the old name */
+    const TCHAR *path_new    /* Pointer to the new name */
+)
+{
+    FRESULT res;
+    FAT_DIR djo, djn;
+    BYTE buf[21], *dir;
+    DWORD dw;
+    DEF_NAMEBUF;
+
+
+    res = chk_mounted(&path_old, &djo.fs, 1);
+    if (res == FR_OK) {
+        djn.fs = djo.fs;
+        INIT_BUF(djo);
+        res = follow_path(&djo, path_old);        /* Check old object */
+        if (_FS_RPATH && res == FR_OK && (djo.fn[NS] & NS_DOT))
+            res = FR_INVALID_NAME;
+#if _FS_SHARE
+        if (res == FR_OK) res = chk_lock(&djo, 2);
+#endif
+        if (res == FR_OK) {                        /* Old object is found */
+            if (!djo.dir) {                        /* Is root dir? */
+                res = FR_NO_FILE;
+            } else {
+                mem_cpy(buf, djo.dir+DIR_Attr, 21);        /* Save the object information except for name */
+                mem_cpy(&djn, &djo, sizeof(FAT_DIR));        /* Check new object */
+                res = follow_path(&djn, path_new);
+                if (res == FR_OK) res = FR_EXIST;            /* The new object name is already existing */
+                if (res == FR_NO_FILE) {                     /* Is it a valid path and no name collision? */
+/* Start critical section that any interruption or error can cause cross-link */
+                    res = dir_register(&djn);            /* Register the new entry */
+                    if (res == FR_OK) {
+                        dir = djn.dir;                    /* Copy object information except for name */
+                        mem_cpy(dir+13, buf+2, 19);
+                        dir[DIR_Attr] = buf[0] | AM_ARC;
+                        djo.fs->wflag = 1;
+                        if (djo.sclust != djn.sclust && (dir[DIR_Attr] & AM_DIR)) {        /* Update .. entry in the directory if needed */
+                            dw = clust2sect(djn.fs, (DWORD)LD_WORD(dir+DIR_FstClusHI) | LD_WORD(dir+DIR_FstClusLO));
+                            if (!dw) {
+                                res = FR_INT_ERR;
+                            } else {
+                                res = move_window(djn.fs, dw);
+                                dir = djn.fs->win+32;    /* .. entry */
+                                if (res == FR_OK && dir[1] == '.') {
+                                    dw = (djn.fs->fs_type == FS_FAT32 && djn.sclust == djn.fs->dirbase) ? 0 : djn.sclust;
+                                    ST_WORD(dir+DIR_FstClusLO, dw);
+                                    ST_WORD(dir+DIR_FstClusHI, dw >> 16);
+                                    djn.fs->wflag = 1;
+                                }
+                            }
+                        }
+                        if (res == FR_OK) {
+                            res = dir_remove(&djo);        /* Remove old entry */
+                            if (res == FR_OK)
+                                res = sync(djo.fs);
+                        }
+                    }
+/* End critical section */
+                }
+            }
+        }
+        FREE_BUF();
+    }
+    LEAVE_FF(djo.fs, res);
+}
+
+#endif /* !_FS_READONLY */
+#endif /* _FS_MINIMIZE == 0 */
+#endif /* _FS_MINIMIZE <= 1 */
+#endif /* _FS_MINIMIZE <= 2 */
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Forward data to the stream directly (available on only tiny cfg)      */
+/*-----------------------------------------------------------------------*/
+#if _USE_FORWARD && _FS_TINY
+
+FRESULT f_forward (
+    FAT_FIL *fp,                         /* Pointer to the file object */
+    UINT (*func)(const BYTE*,UINT),    /* Pointer to the streaming function */
+    UINT btr,                        /* Number of bytes to forward */
+    UINT *bf                        /* Pointer to number of bytes forwarded */
+)
+{
+    FRESULT res;
+    DWORD remain, clst, sect;
+    UINT rcnt;
+    BYTE csect;
+
+
+    *bf = 0;    /* Initialize byte counter */
+
+    res = validate(fp->fs, fp->id);                    /* Check validity of the object */
+    if (res != FR_OK) LEAVE_FF(fp->fs, res);
+    if (fp->flag & FA__ERROR)                        /* Check error flag */
+        LEAVE_FF(fp->fs, FR_INT_ERR);
+    if (!(fp->flag & FA_READ))                        /* Check access mode */
+        LEAVE_FF(fp->fs, FR_DENIED);
+
+    remain = fp->fsize - fp->fptr;
+    if (btr > remain) btr = (UINT)remain;            /* Truncate btr by remaining bytes */
+
+    for ( ;  btr && (*func)(0, 0);                    /* Repeat until all data transferred or stream becomes busy */
+        fp->fptr += rcnt, *bf += rcnt, btr -= rcnt) {
+        csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1));    /* Sector offset in the cluster */
+        if ((fp->fptr % SS(fp->fs)) == 0) {            /* On the sector boundary? */
+            if (!csect) {                            /* On the cluster boundary? */
+                clst = (fp->fptr == 0) ?            /* On the top of the file? */
+                    fp->org_clust : get_fat(fp->fs, fp->curr_clust);
+                if (clst <= 1) ABORT(fp->fs, FR_INT_ERR);
+                if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR);
+                fp->curr_clust = clst;                /* Update current cluster */
+            }
+        }
+        sect = clust2sect(fp->fs, fp->curr_clust);    /* Get current data sector */
+        if (!sect) ABORT(fp->fs, FR_INT_ERR);
+        sect += csect;
+        if (move_window(fp->fs, sect))                /* Move sector window */
+            ABORT(fp->fs, FR_DISK_ERR);
+        fp->dsect = sect;
+        rcnt = SS(fp->fs) - (WORD)(fp->fptr % SS(fp->fs));    /* Forward data from sector window */
+        if (rcnt > btr) rcnt = btr;
+        rcnt = (*func)(&fp->fs->win[(WORD)fp->fptr % SS(fp->fs)], rcnt);
+        if (!rcnt) ABORT(fp->fs, FR_INT_ERR);
+    }
+
+    LEAVE_FF(fp->fs, FR_OK);
+}
+#endif /* _USE_FORWARD */
+
+
+
+#if _USE_MKFS && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Create File System on the Drive                                       */
+/*-----------------------------------------------------------------------*/
+#define N_ROOTDIR    512            /* Multiple of 32 */
+#define N_FATS        1            /* 1 or 2 */
+
+
+FRESULT f_mkfs (
+    BYTE drv,        /* Logical drive number */
+    BYTE sfd,        /* Partitioning rule 0:FDISK, 1:SFD */
+    UINT au            /* Allocation unit size [bytes] */
+)
+{
+    static const WORD vst[] = { 1024,   512,  256,  128,   64,    32,   16,    8,    4,    2,   0};
+    static const WORD cst[] = {32768, 16384, 8192, 4096, 2048, 16384, 8192, 4096, 2048, 1024, 512};
+    BYTE fmt, md, *tbl;
+    DWORD n_clst, vs, n;
+    UINT as, i;
+    DWORD b_vol, b_fat, b_dir, b_data;        /* Area offset (LBA) */
+    DWORD n_vol, n_rsv, n_fat, n_dir;        /* Area size */
+    FATFS *fs;
+    DSTATUS stat;
+
+
+    /* Check mounted drive and clear work area */
+    if (drv >= _DRIVES) return FR_INVALID_DRIVE;
+    fs = FatFs[drv];
+    if (!fs) return FR_NOT_ENABLED;
+    fs->fs_type = 0;
+    drv = LD2PD(drv);
+
+    /* Get disk statics */
+    stat = disk_initialize(drv);
+    if (stat & STA_NOINIT) return FR_NOT_READY;
+    if (stat & STA_PROTECT) return FR_WRITE_PROTECTED;
+#if _MAX_SS != 512                    /* Get disk sector size */
+    if (disk_ioctl(drv, GET_SECTOR_SIZE, &SS(fs)) != RES_OK || SS(fs) > _MAX_SS)
+        return FR_DISK_ERR;
+#endif
+    if (disk_ioctl(drv, GET_SECTOR_COUNT, &n_vol) != RES_OK || n_vol < 128)
+        return FR_DISK_ERR;
+    b_vol = (sfd == 1) ? 0 : 63;    /* Volume start sector */
+    n_vol -= b_vol;
+    if (au & (au - 1)) au = 0;        /* Check validity of the allocation unit size */
+    if (!au) {                        /* AU auto selection */
+        vs = n_vol / (2000 / (SS(fs) / 512));
+        for (i = 0; vs < vst[i]; i++) ;
+        au = cst[i];
+    }
+    if (_MAX_SS != 512 && au < SS(fs)) au = SS(fs);
+    au /= SS(fs);        /* Number of sectors per cluster */
+    if (au == 0) au = 1;
+    if (au > 128) au = 128;
+
+    /* Pre-compute number of clusters and FAT syb-type */
+    n_clst = n_vol / au;
+    fmt = FS_FAT12;
+    if (n_clst >= MIN_FAT16) fmt = FS_FAT16;
+    if (n_clst >= MIN_FAT32) fmt = FS_FAT32;
+
+    /* Determine offset and size of FAT structure */
+    if (fmt == FS_FAT32) {
+        n_fat = ((n_clst * 4) + 8 + SS(fs) - 1) / SS(fs);
+        n_rsv = 32;
+        n_dir = 0;
+    } else {
+        n_fat = (fmt == FS_FAT12) ? (n_clst * 3 + 1) / 2 + 3 : (n_clst * 2) + 4;
+        n_fat = (n_fat + SS(fs) - 1) / SS(fs);
+        n_rsv = 1;
+        n_dir = N_ROOTDIR * 32UL / SS(fs);
+    }
+    b_fat = b_vol + n_rsv;                /* FAT area start sector */
+    b_dir = b_fat + n_fat * N_FATS;        /* Directory area start sector */
+    b_data = b_dir + n_dir;                /* Data area start sector */
+    if (n_vol < b_data + au) return FR_MKFS_ABORTED;    /* Too small volume */
+
+    /* Align data start sector to erase block boundary (for flash memory media) */
+    if (disk_ioctl(drv, GET_BLOCK_SIZE, &n) != RES_OK) return FR_DISK_ERR;
+    if (!n || n > 32768) return FR_MKFS_ABORTED;
+    n = (b_data + n - 1) & ~(n - 1);    /* Next nearest boundary from current data start */
+    n = (n - b_data) / N_FATS;
+    if (fmt == FS_FAT32) {        /* FAT32: Move FAT start */
+        n_rsv += n;
+        b_fat += n;
+    } else {                    /* FAT12/16: Expand FAT size */
+        n_fat += n;
+    }
+    /* b_dir and b_data are no longer used below */
+
+    /* Determine number of cluster and final check of validity of the FAT sub-type */
+    n_clst = (n_vol - n_rsv - n_fat * N_FATS - n_dir) / au;
+    if (   (fmt == FS_FAT16 && n_clst < MIN_FAT16)
+        || (fmt == FS_FAT32 && n_clst < MIN_FAT32))
+        return FR_MKFS_ABORTED;
+
+    /* Create partition table if required */
+    if (sfd == 1) {
+        md = 0xF0;
+    } else {
+        DWORD n_disk = b_vol + n_vol;
+
+        mem_set(fs->win, 0, SS(fs));
+        tbl = fs->win+MBR_Table;
+        ST_DWORD(tbl, 0x00010180);        /* Partition start in CHS */
+        if (n_disk < 63UL * 255 * 1024) {    /* Partition end in CHS */
+            n_disk = n_disk / 63 / 255;
+            tbl[7] = (BYTE)n_disk;
+            tbl[6] = (BYTE)((n_disk >> 2) | 63);
+        } else {
+            ST_WORD(&tbl[6], 0xFFFF);
+        }
+        tbl[5] = 254;
+        if (fmt != FS_FAT32)            /* System ID */
+            tbl[4] = (n_vol < 0x10000) ? 0x04 : 0x06;
+        else
+            tbl[4] = 0x0c;
+        ST_DWORD(tbl+8, 63);            /* Partition start in LBA */
+        ST_DWORD(tbl+12, n_vol);        /* Partition size in LBA */
+        ST_WORD(tbl+64, 0xAA55);        /* Signature */
+        if (disk_write(drv, fs->win, 0, 1) != RES_OK)
+            return FR_DISK_ERR;
+        md = 0xF8;
+    }
+
+    /* Create VBR */
+    tbl = fs->win;                                /* Clear buffer */
+    mem_set(tbl, 0, SS(fs));
+    ST_DWORD(tbl+BS_jmpBoot, 0x90FEEB);            /* Boot code (jmp $, nop) */
+    as = SS(fs);                                /* Sector size */
+    ST_WORD(tbl+BPB_BytsPerSec, as);
+    tbl[BPB_SecPerClus] = (BYTE)au;                /* Sectors per cluster */
+    ST_WORD(tbl+BPB_RsvdSecCnt, n_rsv);            /* Reserved sectors */
+    tbl[BPB_NumFATs] = N_FATS;                    /* Number of FATs */
+    as = (fmt == FS_FAT32) ? 0 : N_ROOTDIR;        /* Number of rootdir entries */
+    ST_WORD(tbl+BPB_RootEntCnt, as);
+    if (n_vol < 0x10000) {                        /* Number of total sectors */
+        ST_WORD(tbl+BPB_TotSec16, n_vol);
+    } else {
+        ST_DWORD(tbl+BPB_TotSec32, n_vol);
+    }
+    tbl[BPB_Media] = md;                        /* Media descriptor */
+    ST_WORD(tbl+BPB_SecPerTrk, 63);                /* Number of sectors per track */
+    ST_WORD(tbl+BPB_NumHeads, 255);                /* Number of heads */
+    ST_DWORD(tbl+BPB_HiddSec, b_vol);            /* Hidden sectors */
+    n = get_fattime();                            /* Use current time as VSN */
+    if (fmt == FS_FAT32) {
+        ST_DWORD(tbl+BS_VolID32, n);            /* VSN */
+        ST_DWORD(tbl+BPB_FATSz32, n_fat);        /* Number of sectors per FAT */
+        ST_DWORD(tbl+BPB_RootClus, 2);            /* Root directory start cluster (2) */
+        ST_WORD(tbl+BPB_FSInfo, 1);                /* FSInfo record offset (VBR+1) */
+        ST_WORD(tbl+BPB_BkBootSec, 6);            /* Backup boot record offset (VBR+6) */
+        tbl[BS_DrvNum32] = 0x80;                /* Drive number */
+        tbl[BS_BootSig32] = 0x29;                /* Extended boot signature */
+        mem_cpy(tbl+BS_VolLab32, "NO NAME    FAT32   ", 19);    /* Volume label, FAT signature */
+    } else {
+        ST_DWORD(tbl+BS_VolID, n);                /* VSN */
+        ST_WORD(tbl+BPB_FATSz16, n_fat);        /* Number of sectors per FAT */
+        tbl[BS_DrvNum] = 0x80;                    /* Drive number */
+        tbl[BS_BootSig] = 0x29;                    /* Extended boot signature */
+        mem_cpy(tbl+BS_VolLab, "NO NAME    FAT     ", 19);    /* Volume label, FAT signature */
+    }
+    ST_WORD(tbl+BS_55AA, 0xAA55);                /* Signature (Offset is fixed here regardless of sector size) */
+    if (disk_write(drv, tbl, b_vol, 1) != RES_OK)    /* Original (VBR) */
+        return FR_DISK_ERR;
+    if (fmt == FS_FAT32)                        /* Backup (VBR+6) */
+        disk_write(drv, tbl, b_vol + 6, 1);
+
+    /* Initialize FAT area */
+    for (i = 0; i < N_FATS; i++) {
+        mem_set(tbl, 0, SS(fs));            /* 1st sector of the FAT  */
+        n = md;                                /* Media descriptor byte */
+        if (fmt != FS_FAT32) {
+            n |= (fmt == FS_FAT12) ? 0x00FFFF00 : 0xFFFFFF00;
+            ST_DWORD(tbl+0, n);                /* Reserve cluster #0-1 (FAT12/16) */
+        } else {
+            n |= 0x0FFFFF00;
+            ST_DWORD(tbl+0, n);                /* Reserve cluster #0-1 (FAT32) */
+            ST_DWORD(tbl+4, 0x0FFFFFFF);
+            ST_DWORD(tbl+8, 0x0FFFFFFF);    /* Reserve cluster #2 for root dir */
+        }
+        if (disk_write(drv, tbl, b_fat++, 1) != RES_OK)
+            return FR_DISK_ERR;
+        mem_set(tbl, 0, SS(fs));        /* Fill following FAT entries with zero */
+        for (n = 1; n < n_fat; n++) {    /* This loop may take a time on FAT32 volume due to many single sector write */
+            if (disk_write(drv, tbl, b_fat++, 1) != RES_OK)
+                return FR_DISK_ERR;
+        }
+    }
+
+    /* Initialize root directory */
+    n = (fmt == FS_FAT32) ? as : n_dir;
+    while (n--) {
+        if (disk_write(drv, tbl, b_fat++, 1) != RES_OK)
+            return FR_DISK_ERR;
+    }
+
+    /* Create FSInfo record if needed */
+    if (fmt == FS_FAT32) {
+        ST_WORD(tbl+BS_55AA, 0xAA55);
+        ST_DWORD(tbl+FSI_LeadSig, 0x41615252);
+        ST_DWORD(tbl+FSI_StrucSig, 0x61417272);
+        ST_DWORD(tbl+FSI_Free_Count, n_clst - 1);
+        ST_DWORD(tbl+FSI_Nxt_Free, 0xFFFFFFFF);
+        disk_write(drv, tbl, b_vol + 1, 1);    /* Original (VBR+1) */
+        disk_write(drv, tbl, b_vol + 7, 1);    /* Backup  (VBR+7) */
+    }
+
+    return (disk_ioctl(drv, CTRL_SYNC, (void*)0) == RES_OK) ? FR_OK : FR_DISK_ERR;
+}
+
+#endif /* _USE_MKFS && !_FS_READONLY */
+
+
+
+
+#if _USE_STRFUNC
+/*-----------------------------------------------------------------------*/
+/* Get a string from the file                                            */
+/*-----------------------------------------------------------------------*/
+TCHAR* f_gets (
+    TCHAR* buff,    /* Pointer to the string buffer to read */
+    int len,        /* Size of string buffer (characters) */
+    FAT_FIL* fil        /* Pointer to the file object */
+)
+{
+    int n = 0;
+    TCHAR c, *p = buff;
+    BYTE s[2];
+    UINT rc;
+
+
+    while (n < len - 1) {            /* Read bytes until buffer gets filled */
+        f_read(fil, s, 1, &rc);
+        if (rc != 1) break;            /* Break on EOF or error */
+        c = s[0];
+#if _LFN_UNICODE                    /* Read a character in UTF-8 encoding */
+        if (c >= 0x80) {
+            if (c < 0xC0) continue;    /* Skip stray trailer */
+            if (c < 0xE0) {            /* Two-byte sequense */
+                f_read(fil, s, 1, &rc);
+                if (rc != 1) break;
+                c = ((c & 0x1F) << 6) | (s[0] & 0x3F);
+                if (c < 0x80) c = '?';
+            } else {
+                if (c < 0xF0) {        /* Three-byte sequense */
+                    f_read(fil, s, 2, &rc);
+                    if (rc != 2) break;
+                    c = (c << 12) | ((s[0] & 0x3F) << 6) | (s[1] & 0x3F);
+                    if (c < 0x800) c = '?';
+                } else {            /* Reject four-byte sequense */
+                    c = '?';
+                }
+            }
+        }
+#endif
+#if _USE_STRFUNC >= 2
+        if (c == '\r') continue;    /* Strip '\r' */
+#endif
+        *p++ = c;
+        n++;
+        if (c == '\n') break;        /* Break on EOL */
+    }
+    *p = 0;
+    return n ? buff : 0;            /* When no data read (eof or error), return with error. */
+}
+
+
+
+#if !_FS_READONLY
+#include <stdarg.h>
+/*-----------------------------------------------------------------------*/
+/* Put a character to the file                                           */
+/*-----------------------------------------------------------------------*/
+int f_putc (
+    TCHAR c,    /* A character to be output */
+    FAT_FIL* fil    /* Pointer to the file object */
+)
+{
+    UINT bw, btw;
+    BYTE s[3];
+
+
+#if _USE_STRFUNC >= 2
+    if (c == '\n') f_putc ('\r', fil);    /* LF -> CRLF conversion */
+#endif
+
+#if _LFN_UNICODE    /* Write the character in UTF-8 encoding */
+    if (c < 0x80) {            /* 7-bit */
+        s[0] = (BYTE)c;
+        btw = 1;
+    } else {
+        if (c < 0x800) {    /* 11-bit */
+            s[0] = (BYTE)(0xC0 | (c >> 6));
+            s[1] = (BYTE)(0x80 | (c & 0x3F));
+            btw = 2;
+        } else {            /* 16-bit */
+            s[0] = (BYTE)(0xE0 | (c >> 12));
+            s[1] = (BYTE)(0x80 | ((c >> 6) & 0x3F));
+            s[2] = (BYTE)(0x80 | (c & 0x3F));
+            btw = 3;
+        }
+    }
+#else                /* Write the character without conversion */
+    s[0] = (BYTE)c;
+    btw = 1;
+#endif
+    f_write(fil, s, btw, &bw);        /* Write the char to the file */
+    return (bw == btw) ? 1 : EOF;    /* Return the result */
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Put a string to the file                                              */
+/*-----------------------------------------------------------------------*/
+int f_puts (
+    const TCHAR* str,    /* Pointer to the string to be output */
+    FAT_FIL* fil            /* Pointer to the file object */
+)
+{
+    int n;
+
+
+    for (n = 0; *str; str++, n++) {
+        if (f_putc(*str, fil) == EOF) return EOF;
+    }
+    return n;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Put a formatted string to the file                                    */
+/*-----------------------------------------------------------------------*/
+int f_printf (
+    FAT_FIL* fil,            /* Pointer to the file object */
+    const TCHAR* str,    /* Pointer to the format string */
+    ...                    /* Optional arguments... */
+)
+{
+    va_list arp;
+    BYTE f, r;
+    UINT i, w;
+    ULONG val;
+    TCHAR c, d, s[16];
+    int res, cc;
+
+
+    va_start(arp, str);
+
+    for (cc = res = 0; cc != EOF; res += cc) {
+        c = *str++;
+        if (c == 0) break;            /* End of string */
+        if (c != '%') {                /* Non escape character */
+            cc = f_putc(c, fil);
+            if (cc != EOF) cc = 1;
+            continue;
+        }
+        w = f = 0;
+        c = *str++;
+        if (c == '0') {                /* Flag: '0' padding */
+            f = 1; c = *str++;
+        }
+        while (IsDigit(c)) {        /* Precision */
+            w = w * 10 + c - '0';
+            c = *str++;
+        }
+        if (c == 'l' || c == 'L') {    /* Prefix: Size is long int */
+            f |= 2; c = *str++;
+        }
+        if (!c) break;
+        d = c;
+        if (IsLower(d)) d -= 0x20;
+        switch (d) {                /* Type is... */
+        case 'S' :                    /* String */
+            cc = f_puts(va_arg(arp, TCHAR*), fil); continue;
+        case 'C' :                    /* Character */
+            cc = f_putc((TCHAR)va_arg(arp, int), fil); continue;
+        case 'B' :                    /* Binary */
+            r = 2; break;
+        case 'O' :                    /* Octal */
+            r = 8; break;
+        case 'D' :                    /* Signed decimal */
+        case 'U' :                    /* Unsigned decimal */
+            r = 10; break;
+        case 'X' :                    /* Hexdecimal */
+            r = 16; break;
+        default:                    /* Unknown */
+            cc = f_putc(c, fil); continue;
+        }
+
+        /* Get an argument */
+        val = (f & 2) ? va_arg(arp, long) : ((d == 'D') ? (long)va_arg(arp, int) : va_arg(arp, unsigned int));
+        if (d == 'D' && (val & 0x80000000)) {
+            val = 0 - val;
+            f |= 4;
+        }
+        /* Put it in numeral string */
+        i = 0;
+        do {
+            d = (TCHAR)(val % r); val /= r;
+            if (d > 9) {
+                d += 7;
+                if (c == 'x') d += 0x20;
+            }
+            s[i++] = d + '0';
+        } while (val && i < sizeof(s) / sizeof(s[0]));
+        if (f & 4) s[i++] = '-';
+        cc = 0;
+        while (i < w-- && cc != EOF) {
+            cc = f_putc((TCHAR)((f & 1) ? '0' : ' '), fil);
+            res++;
+        }
+        do {
+            cc = f_putc(s[--i], fil); 
+            res++;
+        } while (i && cc != EOF);
+        if (cc != EOF) cc = 0;
+    }
+
+    va_end(arp);
+    return (cc == EOF) ? cc : res;
+}
+
+#endif /* !_FS_READONLY */
+#endif /* _USE_STRFUNC */
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/ff.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/ff.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,615 @@
+/*---------------------------------------------------------------------------/
+/  FatFs - FAT file system module include file  R0.08     (C)ChaN, 2010
+/----------------------------------------------------------------------------/
+/ FatFs module is a generic FAT file system module for small embedded systems.
+/ This is a free software that opened for education, research and commercial
+/ developments under license policy of following trems.
+/
+/  Copyright (C) 2010, ChaN, all right reserved.
+/
+/ * The FatFs module is a free software and there is NO WARRANTY.
+/ * No restriction on use. You can use, modify and redistribute it for
+/   personal, non-profit or commercial product UNDER YOUR RESPONSIBILITY.
+/ * Redistributions of source code must retain the above copyright notice.
+/
+/----------------------------------------------------------------------------*/
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#ifndef _FATFS
+#define _FATFS    8085    /* Revision ID */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "integer.h"    /* Basic integer types */
+#include "ffconf.h"        /* FatFs configuration options */
+
+#if _FATFS != _FFCONF
+#error Wrong configuration file (ffconf.h).
+#endif
+
+
+/* DBCS code ranges and SBCS extend char conversion table */
+
+#if _CODE_PAGE == 932    /* Japanese Shift-JIS */
+#define _DF1S    0x81    /* DBC 1st byte range 1 start */
+#define _DF1E    0x9F    /* DBC 1st byte range 1 end */
+#define _DF2S    0xE0    /* DBC 1st byte range 2 start */
+#define _DF2E    0xFC    /* DBC 1st byte range 2 end */
+#define _DS1S    0x40    /* DBC 2nd byte range 1 start */
+#define _DS1E    0x7E    /* DBC 2nd byte range 1 end */
+#define _DS2S    0x80    /* DBC 2nd byte range 2 start */
+#define _DS2E    0xFC    /* DBC 2nd byte range 2 end */
+
+#elif _CODE_PAGE == 936    /* Simplified Chinese GBK */
+#define _DF1S    0x81
+#define _DF1E    0xFE
+#define _DS1S    0x40
+#define _DS1E    0x7E
+#define _DS2S    0x80
+#define _DS2E    0xFE
+
+#elif _CODE_PAGE == 949    /* Korean */
+#define _DF1S    0x81
+#define _DF1E    0xFE
+#define _DS1S    0x41
+#define _DS1E    0x5A
+#define _DS2S    0x61
+#define _DS2E    0x7A
+#define _DS3S    0x81
+#define _DS3E    0xFE
+
+#elif _CODE_PAGE == 950    /* Traditional Chinese Big5 */
+#define _DF1S    0x81
+#define _DF1E    0xFE
+#define _DS1S    0x40
+#define _DS1E    0x7E
+#define _DS2S    0xA1
+#define _DS2E    0xFE
+
+#elif _CODE_PAGE == 437    /* U.S. (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x90,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x49,0x49,0x49,0x8E,0x8F,0x90,0x92,0x92,0x4F,0x99,0x4F,0x55,0x55,0x59,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 720    /* Arabic (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x45,0x41,0x84,0x41,0x86,0x43,0x45,0x45,0x45,0x49,0x49,0x8D,0x8E,0x8F,0x90,0x92,0x92,0x93,0x94,0x95,0x49,0x49,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 737    /* Greek (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x92,0x92,0x93,0x94,0x95,0x96,0x97,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87, \
+                0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0xAA,0x92,0x93,0x94,0x95,0x96,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0x97,0xEA,0xEB,0xEC,0xE4,0xED,0xEE,0xE7,0xE8,0xF1,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 775    /* Baltic (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x91,0xA0,0x8E,0x95,0x8F,0x80,0xAD,0xED,0x8A,0x8A,0xA1,0x8D,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0x95,0x96,0x97,0x97,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xE0,0xA3,0xA3,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xB5,0xB6,0xB7,0xB8,0xBD,0xBE,0xC6,0xC7,0xA5,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE3,0xE8,0xE8,0xEA,0xEA,0xEE,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 850    /* Multilingual Latin 1 (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0xDE,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x59,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \
+                0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE7,0xE9,0xEA,0xEB,0xED,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 852    /* Latin 2 (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xDE,0x8F,0x80,0x9D,0xD3,0x8A,0x8A,0xD7,0x8D,0x8E,0x8F,0x90,0x91,0x91,0xE2,0x99,0x95,0x95,0x97,0x97,0x99,0x9A,0x9B,0x9B,0x9D,0x9E,0x9F, \
+                0xB5,0xD6,0xE0,0xE9,0xA4,0xA4,0xA6,0xA6,0xA8,0xA8,0xAA,0x8D,0xAC,0xB8,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBD,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC6,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD2,0xD3,0xD2,0xD5,0xD6,0xD7,0xB7,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE3,0xD5,0xE6,0xE6,0xE8,0xE9,0xE8,0xEB,0xED,0xED,0xDD,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xEB,0xFC,0xFC,0xFE,0xFF}
+
+#elif _CODE_PAGE == 855    /* Cyrillic (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x81,0x81,0x83,0x83,0x85,0x85,0x87,0x87,0x89,0x89,0x8B,0x8B,0x8D,0x8D,0x8F,0x8F,0x91,0x91,0x93,0x93,0x95,0x95,0x97,0x97,0x99,0x99,0x9B,0x9B,0x9D,0x9D,0x9F,0x9F, \
+                0xA1,0xA1,0xA3,0xA3,0xA5,0xA5,0xA7,0xA7,0xA9,0xA9,0xAB,0xAB,0xAD,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB6,0xB6,0xB8,0xB8,0xB9,0xBA,0xBB,0xBC,0xBE,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD3,0xD3,0xD5,0xD5,0xD7,0xD7,0xDD,0xD9,0xDA,0xDB,0xDC,0xDD,0xE0,0xDF, \
+                0xE0,0xE2,0xE2,0xE4,0xE4,0xE6,0xE6,0xE8,0xE8,0xEA,0xEA,0xEC,0xEC,0xEE,0xEE,0xEF,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF8,0xFA,0xFA,0xFC,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 857    /* Turkish (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0x98,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x98,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9E, \
+                0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA6,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xDE,0x59,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 858    /* Multilingual Latin 1 + Euro (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0xDE,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x59,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \
+                0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE7,0xE9,0xEA,0xEB,0xED,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 862    /* Hebrew (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 866    /* Russian (OEM) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0x90,0x91,0x92,0x93,0x9d,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F,0xF0,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 874    /* Thai (OEM, Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 1250 /* Central Europe (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x8D,0x8E,0x8F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xA3,0xB4,0xB5,0xB6,0xB7,0xB8,0xA5,0xAA,0xBB,0xBC,0xBD,0xBC,0xAF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xFF}
+
+#elif _CODE_PAGE == 1251 /* Cyrillic (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x82,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x80,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x8D,0x8E,0x8F, \
+                0xA0,0xA2,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB2,0xA5,0xB5,0xB6,0xB7,0xA8,0xB9,0xAA,0xBB,0xA3,0xBD,0xBD,0xAF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF}
+
+#elif _CODE_PAGE == 1252 /* Latin 1 (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0xAd,0x9B,0x8C,0x9D,0xAE,0x9F, \
+                0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0x9F}
+
+#elif _CODE_PAGE == 1253 /* Greek (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xA2,0xB8,0xB9,0xBA, \
+                0xE0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xF2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xFB,0xBC,0xFD,0xBF,0xFF}
+
+#elif _CODE_PAGE == 1254 /* Turkish (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x9D,0x9E,0x9F, \
+                0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0x9F}
+
+#elif _CODE_PAGE == 1255 /* Hebrew (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 1256 /* Arabic (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x8C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0x41,0xE1,0x41,0xE3,0xE4,0xE5,0xE6,0x43,0x45,0x45,0x45,0x45,0xEC,0xED,0x49,0x49,0xF0,0xF1,0xF2,0xF3,0x4F,0xF5,0xF6,0xF7,0xF8,0x55,0xFA,0x55,0x55,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 1257 /* Baltic (Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+                0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xA8,0xB9,0xAA,0xBB,0xBC,0xBD,0xBE,0xAF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xFF}
+
+#elif _CODE_PAGE == 1258 /* Vietnam (OEM, Windows) */
+#define _DF1S    0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0xAC,0x9D,0x9E,0x9F, \
+                0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+                0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xEC,0xCD,0xCE,0xCF,0xD0,0xD1,0xF2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xFE,0x9F}
+
+#elif _CODE_PAGE == 1    /* ASCII (for only non-LFN cfg) */
+#define _DF1S    0
+
+#else
+#error Unknown code page
+
+#endif
+
+
+
+/* Definitions corresponds to volume management */
+
+#if _MULTI_PARTITION        /* Multiple partition configuration */
+#define LD2PD(drv) (Drives[drv].pd)    /* Get physical drive# */
+#define LD2PT(drv) (Drives[drv].pt)    /* Get partition# */
+typedef struct {
+    BYTE pd;    /* Physical drive# */
+    BYTE pt;    /* Partition # (0-3) */
+} PARTITION;
+extern const PARTITION Drives[];    /* Logical drive# to physical location conversion table */
+
+#else                        /* Single partition configuration */
+#define LD2PD(drv) (drv)    /* Physical drive# is equal to the logical drive# */
+#define LD2PT(drv) 0        /* Always mounts the 1st partition */
+
+#endif
+
+
+
+/* Type of path name strings on FatFs API */
+
+#if _LFN_UNICODE            /* Unicode string */
+#if !_USE_LFN
+#error _LFN_UNICODE must be 0 in non-LFN cfg.
+#endif
+#ifndef _INC_TCHAR
+typedef WCHAR TCHAR;
+#define _T(x) L ## x
+#define _TEXT(x) L ## x
+#endif
+
+#else                        /* ANSI/OEM string */
+#ifndef _INC_TCHAR
+typedef char TCHAR;
+#define _T(x) x
+#define _TEXT(x) x
+#endif
+
+#endif
+
+
+
+/* Definitions corresponds to file shareing feature */
+
+#if _FS_SHARE
+#if _FS_READONLY
+#error _FS_SHARE must be 0 on R/O cfg.
+#endif
+typedef struct {
+    DWORD clu;                /* File ID 1, directory */
+    WORD idx;                /* File ID 2, index in the directory */
+    WORD ctr;                /* File open counter, 0:none, 0x01..0xFF:read open count, 0x100:in write open */
+} FILESEM;
+#endif
+
+
+
+/* File system object structure (FATFS) */
+
+typedef struct {
+    BYTE    fs_type;        /* FAT sub-type (0:Not mounted) */
+    BYTE    drv;            /* Physical drive number */
+    BYTE    csize;            /* Sectors per cluster (1,2,4...128) */
+    BYTE    n_fats;            /* Number of FAT copies (1,2) */
+    BYTE    wflag;            /* win[] dirty flag (1:must be written back) */
+    BYTE    fsi_flag;        /* fsinfo dirty flag (1:must be written back) */
+    WORD    id;                /* File system mount ID */
+    WORD    n_rootdir;        /* Number of root directory entries (FAT12/16) */
+#if _MAX_SS != 512
+    WORD    ssize;            /* Bytes per sector (512,1024,2048,4096) */
+#endif
+#if _FS_REENTRANT
+    _SYNC_t    sobj;            /* Identifier of sync object */
+#endif
+#if !_FS_READONLY
+    DWORD    last_clust;        /* Last allocated cluster */
+    DWORD    free_clust;        /* Number of free clusters */
+    DWORD    fsi_sector;        /* fsinfo sector (FAT32) */
+#endif
+#if _FS_RPATH
+    DWORD    cdir;            /* Current directory start cluster (0:root) */
+#endif
+    DWORD    n_fatent;        /* Number of FAT entries (= number of clusters + 2) */
+    DWORD    fsize;            /* Sectors per FAT */
+    DWORD    fatbase;        /* FAT start sector */
+    DWORD    dirbase;        /* Root directory start sector (FAT32:Cluster#) */
+    DWORD    database;        /* Data start sector */
+    DWORD    winsect;        /* Current sector appearing in the win[] */
+    BYTE    win[_MAX_SS];    /* Disk access window for Directory, FAT (and Data on tiny cfg) */
+#if _FS_SHARE
+    FILESEM    flsem[_FS_SHARE];    /* File lock semaphores */
+#endif
+} FATFS;
+
+
+
+/* File object structure (FIL) */
+
+typedef struct {
+    FATFS*    fs;                /* Pointer to the owner file system object */
+    WORD    id;                /* Owner file system mount ID */
+    BYTE    flag;            /* File status flags */
+    BYTE    pad1;
+    DWORD    fptr;            /* File read/write pointer */
+    DWORD    fsize;            /* File size */
+    DWORD    org_clust;        /* File start cluster (0 when fsize==0) */
+    DWORD    curr_clust;        /* Current cluster */
+    DWORD    dsect;            /* Current data sector */
+#if !_FS_READONLY
+    DWORD    dir_sect;        /* Sector containing the directory entry */
+    BYTE*    dir_ptr;        /* Ponter to the directory entry in the window */
+#endif
+#if _USE_FASTSEEK
+    DWORD*    cltbl;            /* Pointer to the cluster link map table */
+#endif
+#if _FS_SHARE
+    UINT    lockid;            /* File lock ID */
+#endif
+#if !_FS_TINY
+    BYTE    buf[_MAX_SS];    /* File data read/write buffer */
+#endif
+} FAT_FIL;
+
+
+
+/* Directory object structure (FAT_DIR) */
+
+typedef struct {
+    FATFS*    fs;                /* Pointer to the owner file system object */
+    WORD    id;                /* Owner file system mount ID */
+    WORD    index;            /* Current read/write index number */
+    DWORD    sclust;            /* Table start cluster (0:Root dir) */
+    DWORD    clust;            /* Current cluster */
+    DWORD    sect;            /* Current sector */
+    BYTE*    dir;            /* Pointer to the current SFN entry in the win[] */
+    BYTE*    fn;                /* Pointer to the SFN (in/out) {file[8],ext[3],status[1]} */
+#if _USE_LFN
+    WCHAR*    lfn;            /* Pointer to the LFN working buffer */
+    WORD    lfn_idx;        /* Last matched LFN index number (0xFFFF:No LFN) */
+#endif
+} FAT_DIR;
+
+
+
+/* File status structure (FILINFO) */
+
+typedef struct {
+    DWORD    fsize;            /* File size */
+    WORD    fdate;            /* Last modified date */
+    WORD    ftime;            /* Last modified time */
+    BYTE    fattrib;        /* Attribute */
+    TCHAR    fname[13];        /* Short file name (8.3 format) */
+#if _USE_LFN
+    TCHAR*    lfname;            /* Pointer to the LFN buffer */
+    int     lfsize;            /* Size of LFN buffer [chrs] */
+#endif
+} FILINFO;
+
+
+
+/* File function return code (FRESULT) */
+
+typedef enum {
+    FR_OK = 0,                /* (0) Succeeded */
+    FR_DISK_ERR,            /* (1) A hard error occured in the low level disk I/O layer */
+    FR_INT_ERR,                /* (2) Assertion failed */
+    FR_NOT_READY,            /* (3) The physical drive cannot work */
+    FR_NO_FILE,                /* (4) Could not find the file */
+    FR_NO_PATH,                /* (5) Could not find the path */
+    FR_INVALID_NAME,        /* (6) The path name format is invalid */
+    FR_DENIED,                /* (7) Acces denied due to prohibited access or directory full */
+    FR_EXIST,                /* (8) Acces denied due to prohibited access */
+    FR_INVALID_OBJECT,        /* (9) The file/directory object is invalid */
+    FR_WRITE_PROTECTED,        /* (10) The physical drive is write protected */
+    FR_INVALID_DRIVE,        /* (11) The logical drive number is invalid */
+    FR_NOT_ENABLED,            /* (12) The volume has no work area */
+    FR_NO_FILESYSTEM,        /* (13) There is no valid FAT volume on the physical drive */
+    FR_MKFS_ABORTED,        /* (14) The f_mkfs() aborted due to any parameter error */
+    FR_TIMEOUT,                /* (15) Could not get a grant to access the volume within defined period */
+    FR_LOCKED,                /* (16) The operation is rejected according to the file shareing policy */
+    FR_NOT_ENOUGH_CORE,        /* (17) LFN working buffer could not be allocated */
+    FR_TOO_MANY_OPEN_FILES    /* (18) Number of open files > _FS_SHARE */
+} FRESULT;
+
+
+
+/*--------------------------------------------------------------*/
+/* FatFs module application interface                           */
+
+FRESULT f_mount (BYTE, FATFS*);                        /* Mount/Unmount a logical drive */
+FRESULT f_open (FAT_FIL*, const TCHAR*, BYTE);            /* Open or create a file */
+FRESULT f_read (FAT_FIL*, void*, UINT, UINT*);            /* Read data from a file */
+FRESULT f_lseek (FAT_FIL*, DWORD);                        /* Move file pointer of a file object */
+FRESULT f_close (FAT_FIL*);                                /* Close an open file object */
+FRESULT f_opendir (FAT_DIR*, const TCHAR*);                /* Open an existing directory */
+FRESULT f_readdir (FAT_DIR*, FILINFO*);                    /* Read a directory item */
+FRESULT f_stat (const TCHAR*, FILINFO*);            /* Get file status */
+#if !_FS_READONLY
+FRESULT f_write (FAT_FIL*, const void*, UINT, UINT*);    /* Write data to a file */
+FRESULT f_getfree (const TCHAR*, DWORD*, FATFS**);    /* Get number of free clusters on the drive */
+FRESULT f_truncate (FAT_FIL*);                            /* Truncate file */
+FRESULT f_sync (FAT_FIL*);                                /* Flush cached data of a writing file */
+FRESULT f_unlink (const TCHAR*);                    /* Delete an existing file or directory */
+FRESULT f_mkdir (const TCHAR*);                        /* Create a new directory */
+FRESULT f_chmod (const TCHAR*, BYTE, BYTE);            /* Change attriburte of the file/dir */
+FRESULT f_utime (const TCHAR*, const FILINFO*);        /* Change timestamp of the file/dir */
+FRESULT f_rename (const TCHAR*, const TCHAR*);        /* Rename/Move a file or directory */
+#endif
+#if _USE_FORWARD
+FRESULT f_forward (FAT_FIL*, UINT(*)(const BYTE*,UINT), UINT, UINT*);    /* Forward data to the stream */
+#endif
+#if _USE_MKFS
+FRESULT f_mkfs (BYTE, BYTE, UINT);                    /* Create a file system on the drive */
+#endif
+#if _FS_RPATH
+FRESULT f_chdir (const TCHAR*);                        /* Change current directory */
+FRESULT f_chdrive (BYTE);                            /* Change current drive */
+#endif
+#if _USE_STRFUNC
+int f_putc (TCHAR, FAT_FIL*);                            /* Put a character to the file */
+int f_puts (const TCHAR*, FAT_FIL*);                    /* Put a string to the file */
+int f_printf (FAT_FIL*, const TCHAR*, ...);                /* Put a formatted string to the file */
+TCHAR* f_gets (TCHAR*, int, FAT_FIL*);                    /* Get a string from the file */
+#define f_eof(fp) (((fp)->fptr == (fp)->fsize) ? 1 : 0)
+#define f_error(fp) (((fp)->flag & FA__ERROR) ? 1 : 0)
+#ifndef EOF
+#define EOF (-1)
+#endif
+#endif
+
+
+
+/*--------------------------------------------------------------*/
+/* Additional user defined functions                            */
+
+/* RTC function */
+#if !_FS_READONLY
+DWORD get_fattime (void);
+#endif
+
+/* Unicode support functions */
+#if _USE_LFN                        /* Unicode - OEM code conversion */
+WCHAR ff_convert (WCHAR, UINT);        /* OEM-Unicode bidirectional conversion */
+WCHAR ff_wtoupper (WCHAR);            /* Unicode upper-case conversion */
+#if _USE_LFN == 3                    /* Memory functions */
+void* ff_memalloc (UINT);            /* Allocate memory block */
+void ff_memfree (void*);            /* Free memory block */
+#endif
+#endif
+
+/* Sync functions */
+#if _FS_REENTRANT
+int ff_cre_syncobj (BYTE, _SYNC_t*);/* Create a sync object */
+int ff_del_syncobj (_SYNC_t);        /* Delete a sync object */
+int ff_req_grant (_SYNC_t);            /* Lock sync object */
+void ff_rel_grant (_SYNC_t);        /* Unlock sync object */
+#endif
+
+
+
+
+/*--------------------------------------------------------------*/
+/* Flags and offset address                                     */
+
+
+/* File access control and file status flags (FIL.flag) */
+
+#define    FA_READ                0x01
+#define    FA_OPEN_EXISTING    0x00
+#define FA__ERROR            0x80
+
+#if !_FS_READONLY
+#define    FA_WRITE            0x02
+#define    FA_CREATE_NEW        0x04
+#define    FA_CREATE_ALWAYS    0x08
+#define    FA_OPEN_ALWAYS        0x10
+#define FA__WRITTEN            0x20
+#define FA__DIRTY            0x40
+#endif
+
+
+/* FAT sub type (FATFS.fs_type) */
+
+#define FS_FAT12    1
+#define FS_FAT16    2
+#define FS_FAT32    3
+
+
+/* File attribute bits for directory entry */
+
+#define    AM_RDO    0x01    /* Read only */
+#define    AM_HID    0x02    /* Hidden */
+#define    AM_SYS    0x04    /* System */
+#define    AM_VOL    0x08    /* Volume label */
+#define AM_LFN    0x0F    /* LFN entry */
+#define AM_DIR    0x10    /* Directory */
+#define AM_ARC    0x20    /* Archive */
+#define AM_MASK    0x3F    /* Mask of defined bits */
+
+
+/* Fast seek function */
+#define CREATE_LINKMAP    0xFFFFFFFF
+
+
+/* FatFs refers the members in the FAT structures with byte offset instead of
+/ structure member because there are incompatibility of the packing option
+/ between various compilers. */
+
+#define BS_jmpBoot            0
+#define BS_OEMName            3
+#define BPB_BytsPerSec        11
+#define BPB_SecPerClus        13
+#define BPB_RsvdSecCnt        14
+#define BPB_NumFATs            16
+#define BPB_RootEntCnt        17
+#define BPB_TotSec16        19
+#define BPB_Media            21
+#define BPB_FATSz16            22
+#define BPB_SecPerTrk        24
+#define BPB_NumHeads        26
+#define BPB_HiddSec            28
+#define BPB_TotSec32        32
+#define BS_55AA                510
+
+#define BS_DrvNum            36
+#define BS_BootSig            38
+#define BS_VolID            39
+#define BS_VolLab            43
+#define BS_FilSysType        54
+
+#define BPB_FATSz32            36
+#define BPB_ExtFlags        40
+#define BPB_FSVer            42
+#define BPB_RootClus        44
+#define BPB_FSInfo            48
+#define BPB_BkBootSec        50
+#define BS_DrvNum32            64
+#define BS_BootSig32        66
+#define BS_VolID32            67
+#define BS_VolLab32            71
+#define BS_FilSysType32        82
+
+#define    FSI_LeadSig            0
+#define    FSI_StrucSig        484
+#define    FSI_Free_Count        488
+#define    FSI_Nxt_Free        492
+
+#define MBR_Table            446
+
+#define    DIR_Name            0
+#define    DIR_Attr            11
+#define    DIR_NTres            12
+#define    DIR_CrtTime            14
+#define    DIR_CrtDate            16
+#define    DIR_FstClusHI        20
+#define    DIR_WrtTime            22
+#define    DIR_WrtDate            24
+#define    DIR_FstClusLO        26
+#define    DIR_FileSize        28
+#define    LDIR_Ord            0
+#define    LDIR_Attr            11
+#define    LDIR_Type            12
+#define    LDIR_Chksum            13
+#define    LDIR_FstClusLO        26
+
+
+
+/*--------------------------------*/
+/* Multi-byte word access macros  */
+
+#if _WORD_ACCESS == 1    /* Enable word access to the FAT structure */
+#define    LD_WORD(ptr)        (WORD)(*(WORD*)(BYTE*)(ptr))
+#define    LD_DWORD(ptr)        (DWORD)(*(DWORD*)(BYTE*)(ptr))
+#define    ST_WORD(ptr,val)    *(WORD*)(BYTE*)(ptr)=(WORD)(val)
+#define    ST_DWORD(ptr,val)    *(DWORD*)(BYTE*)(ptr)=(DWORD)(val)
+#else                    /* Use byte-by-byte access to the FAT structure */
+#define    LD_WORD(ptr)        (WORD)(((WORD)*(BYTE*)((ptr)+1)<<8)|(WORD)*(BYTE*)(ptr))
+#define    LD_DWORD(ptr)        (DWORD)(((DWORD)*(BYTE*)((ptr)+3)<<24)|((DWORD)*(BYTE*)((ptr)+2)<<16)|((WORD)*(BYTE*)((ptr)+1)<<8)|*(BYTE*)(ptr))
+#define    ST_WORD(ptr,val)    *(BYTE*)(ptr)=(BYTE)(val); *(BYTE*)((ptr)+1)=(BYTE)((WORD)(val)>>8)
+#define    ST_DWORD(ptr,val)    *(BYTE*)(ptr)=(BYTE)(val); *(BYTE*)((ptr)+1)=(BYTE)((WORD)(val)>>8); *(BYTE*)((ptr)+2)=(BYTE)((DWORD)(val)>>16); *(BYTE*)((ptr)+3)=(BYTE)((DWORD)(val)>>24)
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _FATFS */
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/ffconf.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/ffconf.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,163 @@
+//Modified by Thomas Hamilton, Copyright 2010
+
+/*---------------------------------------------------------------------------/
+/  FatFs - FAT file system module configuration file  R0.08  (C)ChaN, 2010   /
+/----------------------------------------------------------------------------/
+/
+/ CAUTION! Do not forget to make clean the project after any changes to
+/ the configuration options.
+/
+/---------------------------------------------------------------------------*/
+
+#ifndef _FFCONF
+#define _FFCONF 8085    /* Revision ID */
+
+/*---------------------------------------------------------------------------/
+/ Function and Buffer Configurations                                         /
+/---------------------------------------------------------------------------*/
+
+#define _FS_TINY            0       /* 0:Normal or 1:Tiny */
+/* When _FS_TINY is set to 1, FatFs uses the sector buffer in the file system
+/  object instead of the sector buffer in the individual file object for file
+/  data transfer. This reduces memory consumption 512 bytes each file object. */
+
+#define _FS_READONLY        0       /* 0:Read/Write or 1:Read only */
+/* Setting _FS_READONLY to 1 defines read only configuration. This removes
+/  writing functions, f_write, f_sync, f_unlink, f_mkdir, f_chmod, f_rename,
+/  f_truncate and useless f_getfree. */
+
+#define _FS_MINIMIZE        0       /* 0, 1, 2 or 3 */
+/* The _FS_MINIMIZE option defines minimization level to remove some functions.
+/
+/   0: Full function.
+/   1: f_stat, f_getfree, f_unlink, f_mkdir, f_chmod, f_truncate and f_rename
+/      are removed.
+/   2: f_opendir and f_readdir are removed in addition to level 1.
+/   3: f_lseek is removed in addition to level 2. */
+
+#define _USE_STRFUNC        2       /* 0:Disable or 1/2:Enable */
+/* To enable string functions, set _USE_STRFUNC to 1 or 2. */
+
+#define _USE_MKFS           1       /* 0:Disable or 1:Enable */
+/* To enable f_mkfs function, set _USE_MKFS to 1 and set _FS_READONLY to 0 */
+
+#define _USE_FORWARD        0       /* 0:Disable or 1:Enable */
+/* To enable f_forward function, set _USE_FORWARD to 1 and set _FS_TINY to 1. */
+
+#define _USE_FASTSEEK       0       /* 0:Disable or 1:Enable */
+/* To enable fast seek feature, set _USE_FASTSEEK to 1. */
+
+/*---------------------------------------------------------------------------/
+/ Locale and Namespace Configurations
+/----------------------------------------------------------------------------*/
+
+#define _CODE_PAGE          1
+/* The _CODE_PAGE specifies the OEM code page to be used on the target system.
+/  Incorrect setting of the code page can cause a file open failure.
+/
+/   932  - Japanese Shift-JIS (DBCS, OEM, Windows)
+/   936  - Simplified Chinese GBK (DBCS, OEM, Windows)
+/   949  - Korean (DBCS, OEM, Windows)
+/   950  - Traditional Chinese Big5 (DBCS, OEM, Windows)
+/   1250 - Central Europe (Windows)
+/   1251 - Cyrillic (Windows)
+/   1252 - Latin 1 (Windows)
+/   1253 - Greek (Windows)
+/   1254 - Turkish (Windows)
+/   1255 - Hebrew (Windows)
+/   1256 - Arabic (Windows)
+/   1257 - Baltic (Windows)
+/   1258 - Vietnam (OEM, Windows)
+/   437  - U.S. (OEM)
+/   720  - Arabic (OEM)
+/   737  - Greek (OEM)
+/   775  - Baltic (OEM)
+/   850  - Multilingual Latin 1 (OEM)
+/   858  - Multilingual Latin 1 + Euro (OEM)
+/   852  - Latin 2 (OEM)
+/   855  - Cyrillic (OEM)
+/   866  - Russian (OEM)
+/   857  - Turkish (OEM)
+/   862  - Hebrew (OEM)
+/   874  - Thai (OEM, Windows)
+/    1    - ASCII only (Valid for non LFN cfg.) */
+
+#define _USE_LFN            0       /* 0 to 3 */
+#define _MAX_LFN            255     /* Maximum LFN length to handle (12 to 255) */
+/* The _USE_LFN option switches the LFN support.
+/
+/   0: Disable LFN. _MAX_LFN and _LFN_UNICODE have no effect.
+/   1: Enable LFN with static working buffer on the bss. NOT REENTRANT.
+/   2: Enable LFN with dynamic working buffer on the STACK.
+/   3: Enable LFN with dynamic working buffer on the HEAP.
+/
+/  The LFN working buffer occupies (_MAX_LFN + 1) * 2 bytes. When enable LFN,
+/  Unicode handling functions ff_convert() and ff_wtoupper() must be added
+/  to the project. When enable to use heap, memory control functions
+/  ff_memalloc() and ff_memfree() must be added to the project. */
+
+#define _LFN_UNICODE        0       /* 0:ANSI/OEM or 1:Unicode */
+/* To switch the character code set on FatFs API to Unicode,
+/  enable LFN feature and set _LFN_UNICODE to 1. */
+
+#define _FS_RPATH           0       /* 0:Disable or 1:Enable */
+/* When _FS_RPATH is set to 1, relative path feature is enabled and f_chdir,
+/  f_chdrive function are available.
+/  Note that output of the f_readdir fnction is affected by this option. */
+
+/*---------------------------------------------------------------------------/
+/ Physical Drive Configurations
+/----------------------------------------------------------------------------*/
+
+#define _DRIVES             7
+/* Number of volumes (logical drives) to be used. */
+
+#define _MAX_SS             512     /* 512, 1024, 2048 or 4096 */
+/* Maximum sector size to be handled.
+/  Always set 512 for memory card and hard disk but a larger value may be
+/  required for floppy disk (512/1024) and optical disk (512/2048).
+/  When _MAX_SS is larger than 512, GET_SECTOR_SIZE command must be implememted
+/  to the disk_ioctl function. */
+
+#define _MULTI_PARTITION    0       /* 0:Single parition or 1:Multiple partition */
+/* When _MULTI_PARTITION is set to 0, each volume is bound to the same physical
+/ drive number and can mount only first primaly partition. When it is set to 1,
+/ each volume is tied to the partitions listed in Drives[]. */
+
+/*---------------------------------------------------------------------------/
+/ System Configurations
+/----------------------------------------------------------------------------*/
+
+#define _WORD_ACCESS        0       /* 0 or 1 */
+/* Set 0 first and it is always compatible with all platforms. The _WORD_ACCESS
+/  option defines which access method is used to the word data on the FAT volume.
+/
+/   0: Byte-by-byte access.
+/   1: Word access. Do not choose this unless following condition is met.
+/
+/  When the byte order on the memory is big-endian or address miss-aligned word
+/  access results incorrect behavior, the _WORD_ACCESS must be set to 0.
+/  If it is not the case, the value can also be set to 1 to improve the
+/  performance and code size. */
+
+#define _FS_REENTRANT       0       /* 0:Disable or 1:Enable */
+#define _FS_TIMEOUT         1024    /* Timeout period in unit of time ticks */
+#define _SYNC_t             HANDLE  /* O/S dependent type of sync object.
+                                    e.g. HANDLE, OS_EVENT*, ID and etc.. */
+/* Include a header file here to define O/S system calls */
+/* #include <windows.h>, <ucos_ii.h.h>, <semphr.h> or ohters. */
+
+/* The _FS_REENTRANT option switches the reentrancy of the FatFs module.
+/
+/   0: Disable reentrancy. _SYNC_t and _FS_TIMEOUT have no effect.
+/   1: Enable reentrancy. Also user provided synchronization handlers,
+/      ff_req_grant, ff_rel_grant, ff_del_syncobj and ff_cre_syncobj
+/      function must be added to the project. */
+
+#define _FS_SHARE           0       /* 0:Disable or >=1:Enable */
+/* To enable file sharing feature, set _FS_SHARE to >= 1 and also user
+   provided memory handlers, ff_memalloc and ff_memfree function must be
+   added to the project. The value defines number of files can be opened
+   per volume. */
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Core/integer.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Core/integer.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,35 @@
+//Modified by Thomas Hamilton, Copyright 2010
+
+/*--------------------------------------------------------------------*/
+/* Integer type definitions for FatFs module  R0.08     (C)ChaN, 2010 */
+/*--------------------------------------------------------------------*/
+
+#ifndef _INTEGER
+#define _INTEGER
+
+#include "stdint.h"
+
+/* These types must be 16-bit, 32-bit or larger integer */
+typedef int             INT;
+typedef unsigned int    UINT;
+
+/* These types must be 8-bit integer */
+typedef char            CHAR;
+typedef unsigned char   UCHAR;
+typedef unsigned char   BYTE;
+
+/* These types must be 16-bit integer */
+typedef short           SHORT;
+typedef unsigned short  USHORT;
+typedef unsigned short  WORD;
+typedef unsigned short  WCHAR;
+
+/* These types must be 32-bit integer */
+typedef long            LONG;
+typedef unsigned long   ULONG;
+typedef unsigned long   DWORD;
+
+/* Boolean type */
+typedef enum { FALSE = 0, TRUE } BOOL;
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATDirHandle.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATDirHandle.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,50 @@
+/* mbed Microcontroller Library - FATDirHandle
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+ 
+#include "FATDirHandle.h"
+
+FATDirHandle::FATDirHandle(FAT_DIR InputDirStr)
+{
+    DirectoryObject = InputDirStr;
+}
+
+int FATDirHandle::closedir()
+{
+    delete this;
+    return 0;
+}
+
+struct dirent* FATDirHandle::readdir()
+{
+    FILINFO FileInfo;
+    FRESULT Result = f_readdir(&DirectoryObject, &FileInfo);
+    if (Result || !FileInfo.fname[0])
+    {
+        return NULL;
+    }
+    else
+    {
+        for (unsigned char i = 0; i < 13; i++)
+        {
+            CurrentEntry.d_name[i] = ((char*)FileInfo.fname)[i];
+        }
+        return &CurrentEntry;
+    }
+}
+
+void FATDirHandle::rewinddir()
+{
+    DirectoryObject.index = 0;
+}
+
+off_t FATDirHandle::telldir()
+{
+    return (off_t)DirectoryObject.index;
+}
+
+void FATDirHandle::seekdir(off_t location)
+{
+    DirectoryObject.index = (WORD)location;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATDirHandle.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATDirHandle.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,30 @@
+/* mbed Microcontroller Library - FATDirHandle
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#ifndef MBED_FATDIRHANDLE_H
+#define MBED_FATDIRHANDLE_H
+
+#include "stdint.h"
+#include "ff.h"
+#include "mbed.h"
+#include "DirHandle.h"
+#include <stdio.h>
+
+class FATDirHandle : public DirHandle
+{
+    private:
+        FAT_DIR DirectoryObject;
+        struct dirent CurrentEntry;
+
+    public:
+        FATDirHandle(FAT_DIR InputDirStr);
+        virtual int closedir();
+        virtual struct dirent* readdir();
+        virtual void rewinddir();
+        virtual off_t telldir();
+        virtual void seekdir(off_t location);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATFileHandle.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATFileHandle.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,89 @@
+/* mbed Microcontroller Library - FATFileHandle
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#include "FATFileHandle.h"
+
+FATFileHandle::FATFileHandle(FAT_FIL InputFilStr)
+{
+    FileObject = InputFilStr;
+}
+
+ssize_t FATFileHandle::write(const void* buffer, size_t length)
+{
+    UINT ByteWritten;
+    if (f_write(&FileObject, buffer, (UINT)length, &ByteWritten))
+    { 
+        return -1;
+    }
+    else
+    {
+        return (ssize_t)ByteWritten;
+    }
+}
+
+int FATFileHandle::close()
+{
+    if (f_close(&FileObject))
+    {
+        return -1;
+    }
+    else
+    {
+        delete this;
+        return 0;
+    }
+}
+
+ssize_t FATFileHandle::read(void* buffer, size_t length)
+{
+    UINT ByteRead;
+    if (f_read(&FileObject, buffer, (UINT)length, &ByteRead))
+    {
+        return -1;
+    }
+    else
+    {
+        return (ssize_t)ByteRead;
+    }
+}
+
+int FATFileHandle::isatty()
+{
+    return 0;
+}
+
+off_t FATFileHandle::lseek(off_t offset, int whence)
+{
+    switch (whence)
+    {
+        case SEEK_CUR: offset += FileObject.fptr; break;
+        case SEEK_END: offset += FileObject.fsize; break;
+    }
+    if (f_lseek(&FileObject, (DWORD)offset))
+    {
+        return -1;
+    }
+    else
+    {
+        return (off_t)FileObject.fptr;
+    }
+}
+
+int FATFileHandle::fsync()
+{
+    if (f_sync(&FileObject))
+    {
+        return -1;
+    }
+    else
+    {
+        return 0;
+    }
+}
+
+off_t FATFileHandle::flen()
+{
+    return (off_t)FileObject.fsize;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATFileHandle.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATFileHandle.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,31 @@
+/* mbed Microcontroller Library - FATFileHandle
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#ifndef MBED_FATFILEHANDLE_H
+#define MBED_FATFILEHANDLE_H
+
+#include "stdint.h"
+#include "ff.h"
+#include "mbed.h"
+#include "FileHandle.h"
+#include <stdio.h>
+
+class FATFileHandle : public FileHandle
+{
+    private:
+        FAT_FIL FileObject;
+
+    public:
+        FATFileHandle(FAT_FIL InputFilStr);
+        virtual ssize_t write(const void* buffer, size_t length);
+        virtual int close();
+        virtual ssize_t read(void* buffer, size_t length);
+        virtual int isatty();
+        virtual off_t lseek(off_t offset, int whence);
+        virtual int fsync();
+        virtual off_t flen();
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATFileSystem.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATFileSystem.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,155 @@
+/* mbed Microcontroller Library - FATFileSystem
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#include "FATFileSystem.h"
+
+DWORD get_fattime(void)
+{
+    return 35719201;
+}
+
+FATFileSystem* FATFileSystem::DriveArray[_DRIVES] = {0};
+
+FATFileSystem::FATFileSystem(const char* SystemName) : FileSystemLike(SystemName)
+{
+    for (unsigned char i = 0; i < _DRIVES; i++)
+    {
+        if(!DriveArray[i])
+        {
+            DriveArray[i] = this;
+            Drive = i;
+            f_mount((BYTE)i, &FileSystemObject);
+            return;
+        }
+    }
+}
+
+FATFileSystem::~FATFileSystem()
+{
+    for (unsigned char i = 0; i < _DRIVES; i++)
+    {
+        if (DriveArray[i] == this)
+        {
+            DriveArray[i] = NULL;
+            f_mount((BYTE)i, NULL);
+        }
+    }
+    delete this;
+}
+
+FileHandle* FATFileSystem::open(const char* filename, int flags)
+{
+    FAT_FIL FileObject;
+    char FileName[64];
+    BYTE ModeFlags = 0;
+
+    sprintf(FileName, "%d:/%s", Drive, filename);
+    switch (flags & 3)
+    {
+        case O_RDONLY: ModeFlags = FA_READ; break;
+        case O_WRONLY: ModeFlags = FA_WRITE; break;
+        case O_RDWR: ModeFlags = FA_READ | FA_WRITE; break;
+    }
+    if(flags & O_CREAT)
+    {
+        if(flags & O_TRUNC)
+        {
+            ModeFlags |= FA_CREATE_ALWAYS;
+        }
+        else
+        {
+            ModeFlags |= FA_OPEN_ALWAYS;
+        }
+    }
+    else
+    {
+        ModeFlags |= FA_OPEN_EXISTING;
+    }
+    if (f_open(&FileObject, (const TCHAR*)FileName, ModeFlags))
+    { 
+        return NULL;
+    }
+    else
+    {
+        if (flags & O_APPEND)
+        {
+            f_lseek(&FileObject, (DWORD)FileObject.fsize);
+        }
+        return new FATFileHandle(FileObject);
+    }
+}
+
+int FATFileSystem::remove(const char* filename)
+{
+    char FileName[64];
+
+    sprintf(FileName, "%d:/%s", Drive, filename);
+    if (f_unlink((const TCHAR*)FileName))
+    { 
+        return -1;
+    }
+    else
+    {
+        return 0;
+    }
+}
+
+int FATFileSystem::rename(const char* oldname, const char* newname)
+{
+    char OldName[64];
+
+    sprintf(OldName, "%d:/%s", Drive, oldname);
+    if (f_rename((const TCHAR*)OldName, (const TCHAR*)newname))
+    {
+        return -1;
+    }
+    else
+    {
+        return 0;
+    }
+}
+
+DirHandle* FATFileSystem::opendir(const char* name)
+{
+    FAT_DIR DirectoryObject;
+    char DirectoryName[64];
+
+    sprintf(DirectoryName, "%d:%s", Drive, name);
+    if (f_opendir(&DirectoryObject, (const TCHAR*)DirectoryName))
+    {
+        return NULL;
+    }
+    else
+    {
+        return new FATDirHandle(DirectoryObject);
+    }
+}
+
+int FATFileSystem::mkdir(const char* name, mode_t mode)
+{
+    char DirectoryName[64];
+
+    sprintf(DirectoryName, "%d:%s", Drive, name);
+    if (f_mkdir((const TCHAR*)DirectoryName))
+    {
+        return -1;
+    }
+    else
+    {
+        return 0;
+    }
+}
+
+int FATFileSystem::format(unsigned int allocationunit)
+{
+    if (f_mkfs(Drive, 0, allocationunit))
+    {
+        return -1;
+    }
+    else
+    {
+        return 0;
+    }
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/FATFileSystem/Interface/FATFileSystem.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/FATFileSystem/Interface/FATFileSystem.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,49 @@
+/* mbed Microcontroller Library - FATFileSystem
+   Copyright (c) 2008, sford */
+
+//Modified by Thomas Hamilton, Copyright 2010
+
+#ifndef MBED_FATFILESYSTEM_H
+#define MBED_FATFILESYSTEM_H
+
+#include "stdint.h"
+#include "ff.h"
+#include "mbed.h"
+#include "FileSystemLike.h"
+#include "FATFileHandle.h"
+#include "FATDirHandle.h"
+#include <stdio.h>
+
+class FATFileSystem : public FileSystemLike
+{
+    private:
+        FATFS FileSystemObject;
+        unsigned char Drive;
+
+    public:
+        static FATFileSystem* DriveArray[_DRIVES];
+
+        FATFileSystem(const char* SystemName);
+        virtual ~FATFileSystem();
+        
+        int format(unsigned int allocationunit);
+
+        virtual FileHandle* open(const char* filename, int flags);
+        virtual int remove(const char* filename);
+        virtual int rename(const char* oldname, const char* newname);
+        virtual DirHandle* opendir(const char* name);
+        virtual int mkdir(const char* name, mode_t mode);
+
+        virtual int disk_initialize() { return 0x00; }
+        virtual int disk_status() { return 0x00; }
+        virtual int disk_read(unsigned char* buff,
+            unsigned long sector, unsigned char count) = 0;
+        virtual int disk_write(const unsigned char* buff,
+            unsigned long sector, unsigned char count) = 0;
+        virtual int disk_sync() { return 0x00; }
+        virtual unsigned long disk_sector_count() = 0;
+        virtual unsigned short disk_sector_size() { return 512; }
+        virtual unsigned long disk_block_size() { return 1; }
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/SDHCFileSystem.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/SDHCFileSystem.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,495 @@
+/* mbed SDFileSystem Library, for providing file access to SD cards
+ * Copyright (c) 2008-2010, sford
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/* Introduction
+ * ------------
+ * SD and MMC cards support a number of interfaces, but common to them all
+ * is one based on SPI. This is the one I'm implmenting because it means
+ * it is much more portable even though not so performant, and we already 
+ * have the mbed SPI Interface!
+ *
+ * The main reference I'm using is Chapter 7, "SPI Mode" of: 
+ *  http://www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf
+ *
+ * SPI Startup
+ * -----------
+ * The SD card powers up in SD mode. The SPI interface mode is selected by
+ * asserting CS low and sending the reset command (CMD0). The card will 
+ * respond with a (R1) response.
+ *
+ * CMD8 is optionally sent to determine the voltage range supported, and 
+ * indirectly determine whether it is a version 1.x SD/non-SD card or 
+ * version 2.x. I'll just ignore this for now.
+ *
+ * ACMD41 is repeatedly issued to initialise the card, until "in idle"
+ * (bit 0) of the R1 response goes to '0', indicating it is initialised.
+ *
+ * You should also indicate whether the host supports High Capicity cards,
+ * and check whether the card is high capacity - i'll also ignore this
+ *
+ * SPI Protocol
+ * ------------
+ * The SD SPI protocol is based on transactions made up of 8-bit words, with
+ * the host starting every bus transaction by asserting the CS signal low. The
+ * card always responds to commands, data blocks and errors.
+ * 
+ * The protocol supports a CRC, but by default it is off (except for the 
+ * first reset CMD0, where the CRC can just be pre-calculated, and CMD8)
+ * I'll leave the CRC off I think! 
+ * 
+ * Standard capacity cards have variable data block sizes, whereas High 
+ * Capacity cards fix the size of data block to 512 bytes. I'll therefore
+ * just always use the Standard Capacity cards with a block size of 512 bytes.
+ * This is set with CMD16.
+ *
+ * You can read and write single blocks (CMD17, CMD25) or multiple blocks 
+ * (CMD18, CMD25). For simplicity, I'll just use single block accesses. When
+ * the card gets a read command, it responds with a response token, and then 
+ * a data token or an error.
+ * 
+ * SPI Command Format
+ * ------------------
+ * Commands are 6-bytes long, containing the command, 32-bit argument, and CRC.
+ *
+ * +---------------+------------+------------+-----------+----------+--------------+
+ * | 01 | cmd[5:0] | arg[31:24] | arg[23:16] | arg[15:8] | arg[7:0] | crc[6:0] | 1 |
+ * +---------------+------------+------------+-----------+----------+--------------+
+ *
+ * As I'm not using CRC, I can fix that byte to what is needed for CMD0 (0x95)
+ *
+ * All Application Specific commands shall be preceded with APP_CMD (CMD55).
+ *
+ * SPI Response Format
+ * -------------------
+ * The main response format (R1) is a status byte (normally zero). Key flags:
+ *  idle - 1 if the card is in an idle state/initialising 
+ *  cmd  - 1 if an illegal command code was detected
+ *
+ *    +-------------------------------------------------+
+ * R1 | 0 | arg | addr | seq | crc | cmd | erase | idle |
+ *    +-------------------------------------------------+
+ *
+ * R1b is the same, except it is followed by a busy signal (zeros) until
+ * the first non-zero byte when it is ready again.
+ *
+ * Data Response Token
+ * -------------------
+ * Every data block written to the card is acknowledged by a byte 
+ * response token
+ *
+ * +----------------------+
+ * | xxx | 0 | status | 1 |
+ * +----------------------+
+ *              010 - OK!
+ *              101 - CRC Error
+ *              110 - Write Error
+ *
+ * Single Block Read and Write
+ * ---------------------------
+ *
+ * Block transfers have a byte header, followed by the data, followed
+ * by a 16-bit CRC. In our case, the data will always be 512 bytes.
+ *  
+ * +------+---------+---------+- -  - -+---------+-----------+----------+
+ * | 0xFE | data[0] | data[1] |        | data[n] | crc[15:8] | crc[7:0] | 
+ * +------+---------+---------+- -  - -+---------+-----------+----------+
+ */
+ 
+ /*
+ * Comment: Changes for SDHC support till 32GB 
+ * Name:    KB
+ * Date:    07/24/2010
+ * Release: 0.1
+ */
+ 
+#include "SDHCFileSystem.h"
+
+#define DEBUG
+#define SD_COMMAND_TIMEOUT 5000
+
+
+SDFileSystem::SDFileSystem(PinName mosi, PinName miso, PinName sclk, PinName cs, const char* name) :
+  FATFileSystem(name), _spi(mosi, miso, sclk), _cs(cs) {
+      _cs = 1; 
+}
+
+#define R1_IDLE_STATE           (1 << 0)
+#define R1_ERASE_RESET          (1 << 1)
+#define R1_ILLEGAL_COMMAND      (1 << 2)
+#define R1_COM_CRC_ERROR        (1 << 3)
+#define R1_ERASE_SEQUENCE_ERROR (1 << 4)
+#define R1_ADDRESS_ERROR        (1 << 5)
+#define R1_PARAMETER_ERROR      (1 << 6)
+
+// Types
+//  - v1.x Standard Capacity
+//  - v2.x Standard Capacity
+//  - v2.x High Capacity
+//  - Not recognised as an SD Card
+
+#define SDCARD_FAIL 0
+#define SDCARD_V1   1
+#define SDCARD_V2   2
+#define SDCARD_V2HC 3
+
+int SDFileSystem::initialise_card() {
+    // Set to 100kHz for initialisation, and clock card with cs = 1
+    _spi.frequency(100000); 
+    _cs = 1;
+    for(int i=0; i<16; i++) {   
+        _spi.write(0xFF);
+    }
+
+    // send CMD0, should return with all zeros except IDLE STATE set (bit 0)
+    if(_cmd(0, 0) != R1_IDLE_STATE) { 
+        fprintf(stderr, "No disk, or could not put SD card in to SPI idle state\n");
+        return SDCARD_FAIL;
+    }
+
+    // send CMD8 to determine whther it is ver 2.x
+    int r = _cmd8();
+    if(r == R1_IDLE_STATE) {
+        return initialise_card_v2();
+    } else if(r == (R1_IDLE_STATE | R1_ILLEGAL_COMMAND)) {
+        return initialise_card_v1();
+    } else {
+        fprintf(stderr, "Not in idle state after sending CMD8 (not an SD card?)\n");
+        return SDCARD_FAIL;
+    }
+}
+
+int SDFileSystem::initialise_card_v1() {
+    for(int i=0; i<SD_COMMAND_TIMEOUT; i++) {
+        _cmd(55, 0); 
+        if(_cmd(41, 0) == 0) { 
+            cdv = 512;
+            #ifdef DEBUG 
+            printf("\n\rInit: SEDCARD_V1\n\r");
+            #endif
+            return SDCARD_V1;
+        }
+    }
+
+    fprintf(stderr, "Timeout waiting for v1.x card\n");
+    return SDCARD_FAIL;
+}
+
+int SDFileSystem::initialise_card_v2() {
+    
+    for(int i=0; i<SD_COMMAND_TIMEOUT; i++) {
+        wait_ms(50);
+        _cmd58();
+        _cmd(55, 0); 
+        if(_cmd(41, 0x40000000) == 0) { 
+            _cmd58();
+            #ifdef DEBUG
+            printf("\n\rInit: SDCARD_V2\n\r");
+            #endif
+            cdv = 1;
+            return SDCARD_V2;
+        }
+    }
+
+    fprintf(stderr, "Timeout waiting for v2.x card\n");
+    return SDCARD_FAIL;
+}
+
+int SDFileSystem::disk_initialize() {
+
+    int i = initialise_card();
+    #ifdef DEBUG 
+    printf("init card = %d\n", i);
+    #endif
+    _sectors = _sd_sectors();
+
+    // Set block length to 512 (CMD16)
+    if(_cmd(16, 512) != 0) {
+        fprintf(stderr, "Set 512-byte block timed out\n");
+        return 1;
+    }
+        
+    _spi.frequency(1000000); // Set to 1MHz for data transfer
+    return 0;
+}
+
+int SDFileSystem::disk_write(const unsigned char *buffer, unsigned long block_number, unsigned char count) {
+    // set write address for single block (CMD24)
+    if(_cmd(24, block_number * cdv) != 0) {
+        return 1;
+    }
+
+    // send the data block
+    _write(buffer, 512);    
+    return 0;    
+}
+
+int SDFileSystem::disk_read(unsigned char *buffer, unsigned long block_number, unsigned char count) {        
+    // set read address for single block (CMD17)
+    if(_cmd(17, block_number * cdv) != 0) {
+        return 1;
+    }
+    
+    // receive the data
+    _read(buffer, 512);
+    return 0;
+}
+
+int SDFileSystem::disk_status() { return 0; }
+int SDFileSystem::disk_sync() { return 0; }
+unsigned long SDFileSystem::disk_sector_count() { return _sectors; }
+
+// PRIVATE FUNCTIONS
+
+int SDFileSystem::_cmd(int cmd, int arg) {
+    _cs = 0; 
+
+    // send a command
+    _spi.write(0x40 | cmd);
+    _spi.write(arg >> 24);
+    _spi.write(arg >> 16);
+    _spi.write(arg >> 8);
+    _spi.write(arg >> 0);
+    _spi.write(0x95);
+
+    // wait for the repsonse (response[7] == 0)
+    for(int i=0; i<SD_COMMAND_TIMEOUT; i++) {
+        int response = _spi.write(0xFF);
+        if(!(response & 0x80)) {
+            _cs = 1;
+            _spi.write(0xFF);
+            return response;
+        }
+    }
+    _cs = 1;
+    _spi.write(0xFF);
+    return -1; // timeout
+}
+int SDFileSystem::_cmdx(int cmd, int arg) {
+    _cs = 0; 
+
+    // send a command
+    _spi.write(0x40 | cmd);
+    _spi.write(arg >> 24);
+    _spi.write(arg >> 16);
+    _spi.write(arg >> 8);
+    _spi.write(arg >> 0);
+    _spi.write(0x95);
+
+    // wait for the repsonse (response[7] == 0)
+    for(int i=0; i<SD_COMMAND_TIMEOUT; i++) {
+        int response = _spi.write(0xFF);
+        if(!(response & 0x80)) {
+            return response;
+        }
+    }
+    _cs = 1;
+    _spi.write(0xFF);
+    return -1; // timeout
+}
+
+
+int SDFileSystem::_cmd58() {
+    _cs = 0; 
+    int arg = 0;
+    
+    // send a command
+    _spi.write(0x40 | 58);
+    _spi.write(arg >> 24);
+    _spi.write(arg >> 16);
+    _spi.write(arg >> 8);
+    _spi.write(arg >> 0);
+    _spi.write(0x95);
+
+    // wait for the repsonse (response[7] == 0)
+    for(int i=0; i<SD_COMMAND_TIMEOUT; i++) {
+        int response = _spi.write(0xFF);
+        if(!(response & 0x80)) {
+            int ocr = _spi.write(0xFF) << 24;
+            ocr |= _spi.write(0xFF) << 16;
+            ocr |= _spi.write(0xFF) << 8;
+            ocr |= _spi.write(0xFF) << 0;
+//            printf("OCR = 0x%08X\n", ocr);
+            _cs = 1;
+            _spi.write(0xFF);
+            return response;
+        }
+    }
+    _cs = 1;
+    _spi.write(0xFF);
+    return -1; // timeout
+}
+
+int SDFileSystem::_cmd8() {
+    _cs = 0; 
+    
+    // send a command
+    _spi.write(0x40 | 8); // CMD8
+    _spi.write(0x00);     // reserved
+    _spi.write(0x00);     // reserved
+    _spi.write(0x01);     // 3.3v
+    _spi.write(0xAA);     // check pattern
+    _spi.write(0x87);     // crc
+
+    // wait for the repsonse (response[7] == 0)
+    for(int i=0; i<SD_COMMAND_TIMEOUT * 1000; i++) {
+        char response[5];
+        response[0] = _spi.write(0xFF);
+        if(!(response[0] & 0x80)) {
+                for(int j=1; j<5; j++) {
+                    response[i] = _spi.write(0xFF);
+                }
+                _cs = 1;
+                _spi.write(0xFF);
+                return response[0];
+        }
+    }
+    _cs = 1;
+    _spi.write(0xFF);
+    return -1; // timeout
+}
+
+int SDFileSystem::_read(unsigned char *buffer, int length) {
+    _cs = 0;
+
+    // read until start byte (0xFF)
+    while(_spi.write(0xFF) != 0xFE);
+
+    // read data
+    for(int i=0; i<length; i++) {
+        buffer[i] = _spi.write(0xFF);
+    }
+    _spi.write(0xFF); // checksum
+    _spi.write(0xFF);
+
+    _cs = 1;    
+    _spi.write(0xFF);
+    return 0;
+}
+
+int SDFileSystem::_write(const unsigned char *buffer, int length) {
+    _cs = 0;
+    
+    // indicate start of block
+    _spi.write(0xFE);
+    
+    // write the data
+    for(int i=0; i<length; i++) {
+        _spi.write(buffer[i]);
+    }
+    
+    // write the checksum
+    _spi.write(0xFF); 
+    _spi.write(0xFF);
+
+    // check the repsonse token
+    if((_spi.write(0xFF) & 0x1F) != 0x05) {
+        _cs = 1;
+        _spi.write(0xFF);        
+        return 1;
+    }
+
+    // wait for write to finish
+    while(_spi.write(0xFF) == 0);
+
+    _cs = 1; 
+    _spi.write(0xFF);
+    return 0;
+}
+
+static int ext_bits(unsigned char *data, int msb, int lsb) {
+    int bits = 0;
+    int size = 1 + msb - lsb; 
+    for(int i=0; i<size; i++) {
+        int position = lsb + i;
+        int byte = 15 - (position >> 3);
+        int bit = position & 0x7;
+        int value = (data[byte] >> bit) & 1;
+        bits |= value << i;
+    }
+    return bits;
+}
+
+unsigned long SDFileSystem::_sd_sectors() {
+
+    int c_size, c_size_mult, read_bl_len;
+    int block_len, mult, blocknr, capacity;       
+    int blocks, hc_c_size;
+    uint64_t hc_capacity;
+     
+    // CMD9, Response R2 (R1 byte + 16-byte block read)
+    if(_cmdx(9, 0) != 0) {
+        fprintf(stderr, "Didn't get a response from the disk\n");
+        return 0;
+    }
+    
+    unsigned char csd[16];    
+    if(_read(csd, 16) != 0) {
+        fprintf(stderr, "Couldn't read csd response from disk\n");
+        return 0;
+    }
+
+    // csd_structure : csd[127:126]
+    // c_size        : csd[73:62]
+    // c_size_mult   : csd[49:47]
+    // read_bl_len   : csd[83:80] - the *maximum* read block length
+   
+    int csd_structure = ext_bits(csd, 127, 126);
+    
+    #ifdef DEBUG 
+    printf("\n\rCSD_STRUCT = %d\n", csd_structure);
+    #endif
+    //int hc_read_bl_len;
+     
+    switch (csd_structure) {
+     case 0:
+      cdv = 512;
+      c_size = ext_bits(csd, 73, 62);
+      c_size_mult = ext_bits(csd, 49, 47);
+      read_bl_len = ext_bits(csd, 83, 80);
+     
+      block_len = 1 << read_bl_len;
+      mult = 1 << (c_size_mult + 2);
+      blocknr = (c_size + 1) * mult;
+      capacity = blocknr * block_len;
+      blocks = capacity / 512;
+      #ifdef DEBUG 
+      printf("\n\rSDCard\n\rc_size: %.4X \n\rcapacity: %.ld \n\rsectors: %d\n\r", c_size, capacity, blocks);
+      #endif
+      break;
+    
+     case 1:
+      cdv = 1;
+      hc_c_size = ext_bits(csd, 63, 48);
+      //hc_read_bl_len = ext_bits(csd, 83, 80);
+      hc_capacity = hc_c_size+1;   
+      blocks = (hc_c_size+1)*1024;
+      #ifdef DEBUG 
+      printf("\n\rSDHC Card \n\rhc_c_size: %.4X \n\rcapacity: %.lld \n\rsectors: %d\n\r", hc_c_size, hc_capacity*512*1024, blocks);
+      #endif
+      break;
+   
+    default:    
+       fprintf(stderr, "This disk tastes funny! I only know about type 0 CSD structures\n");
+       return 0;
+    };
+ return blocks;
+}
diff -r 000000000000 -r 826c6171fc1b SDFileSystem/SDHCFileSystem.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SDFileSystem/SDHCFileSystem.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,88 @@
+/* mbed SDFileSystem Library, for providing file access to SD cards
+ * Copyright (c) 2008-2010, sford
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#ifndef MBED_SDHCFILESYSTEM_H
+#define MBED_SDHCFILESYSTEM_H
+
+/** Implements FAT32 filesystem on SDHC cards, Copyright (c) 2008-2010, sford */
+
+#include "mbed.h"
+#include "FATFileSystem.h"
+
+/* Double Words */
+typedef unsigned long long uint64_t;
+typedef long long sint64_t;
+
+/** Access the filesystem on an SD Card using SPI
+ *
+ * @code
+ * #include "mbed.h"
+ * #include "SDFileSystem.h"
+ *
+ * SDFileSystem sd(p5, p6, p7, p12, "sd"); // mosi, miso, sclk, cs
+ *  
+ * int main() {
+ *     FILE *fp = fopen("/sd/myfile.txt", "w");
+ *     fprintf(fp, "Hello World!\n");
+ *     fclose(fp);
+ * }
+ */
+class SDFileSystem : public FATFileSystem {
+public:
+
+    /** Create the File System for accessing an SD Card using SPI
+     *
+     * @param mosi SPI mosi pin connected to SD Card
+     * @param miso SPI miso pin conencted to SD Card
+     * @param sclk SPI sclk pin connected to SD Card
+     * @param cs   DigitalOut pin used as SD Card chip select
+     * @param name The name used to access the virtual filesystem
+     */
+    SDFileSystem(PinName mosi, PinName miso, PinName sclk, PinName cs, const char* name);
+    virtual int disk_initialize();
+    virtual int disk_status();
+    virtual int disk_read(unsigned char *buffer, unsigned long block_number, unsigned char count);    
+    virtual int disk_write(const unsigned char *buffer, unsigned long block_number, unsigned char count);
+    virtual int disk_sync();
+    virtual unsigned long disk_sector_count();
+
+protected:
+
+    int _cmd(int cmd, int arg);
+    int _cmdx(int cmd, int arg);
+    int _cmd8();
+    int _cmd58();
+    int initialise_card();
+    int initialise_card_v1();
+    int initialise_card_v2();
+    
+    int _read(unsigned char *buffer, int length);
+    int _write(const unsigned char *buffer, int length);
+    unsigned long _sd_sectors();
+    unsigned long _sectors;
+    
+    SPI _spi;
+    DigitalOut _cs; 
+    int cdv;    
+};
+
+#endif
diff -r 000000000000 -r 826c6171fc1b Schedule.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Schedule.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/shimniok/code/Schedule/#03d36a9a088b
diff -r 000000000000 -r 826c6171fc1b Sensors/Camera/Camera.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/Camera/Camera.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,56 @@
+#include "mbed.h"
+#include "Camera.h"
+
+Camera::Camera(PinName tx, PinName rx):
+    serial(tx, rx)
+{
+    serial.baud(115200);
+
+    return;
+} 
+
+void Camera::start()
+{
+    serial.attach(this, &Camera::receive, Serial::RxIrq);
+    
+    // ping
+    // should now get ACK\r or NACK\r
+    // send colormap here
+    // should now get ACK\r or NACK\r
+    // disable white balance
+    // should now get ACK\r or NACK\r
+    serial.printf("ET\r\n");
+    // should now get ACK\r or NACK\r
+    return;
+}
+
+
+void Camera::receive()
+{
+    while (serial.readable()) {
+        char c = serial.getc();
+        fprintf(stdout, "%c\n", c);
+    }
+    return;
+}
+
+
+/*
+ * (Byte 0: 0x0A – Indicating the start of a tracking packet 
+ * Byte 1: Number of trac k ed objects (0x00 – 0x08 are valid) 
+ * Byte 2: Color of object tracked in bounding box 1 
+ * Byte 3: X upper left corner of bounding box 1 
+ * Byte 4: Y upper left corner of bouding box 1 
+ * Byte 5: X lower right corner of boudning box 1 
+ * Byte 6: Y lower right corner of boudning box 1 
+ * Byte 7: Color object tracked in bound box 2 
+ * ... 
+ * Byte x: 0xFF (indicates the end of line, and will be sent after all tracking info  
+ * for the current frame has been sent)   
+ */
+void Camera::parse(char c)
+{
+
+    return;
+}
+
diff -r 000000000000 -r 826c6171fc1b Sensors/Camera/Camera.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/Camera/Camera.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,21 @@
+#ifndef __CAMERA_H
+#define __CAMERA_H
+
+
+#define CAM_WAIT_ACK    0x01
+#define CAM_PARSE_TRACK 0x02
+
+#define CAM_ACK         0x00
+#define CAM_NACK        0x01
+
+class Camera {
+public:
+    Camera(PinName tx, PinName rx);
+    void start(void);
+    void receive(void);
+    void parse(char c);
+    
+    int lastStatus;
+    Serial serial;
+};    
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/GPS/GPS.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/GPS/GPS.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,176 @@
+// For SiRF III
+
+#include "GPS.h"
+
+extern Serial pc;
+
+
+
+
+GPS::GPS(PinName tx, PinName rx, int type):
+    hdop(0.0),
+    serial(tx, rx)
+{
+    setType(SIRF);
+    setBaud(4800);
+} 
+
+
+void GPS::setType(int type)
+{
+    if (type == VENUS || type == MTK || type == SIRF) {
+        _type = type;
+    }
+    
+    return;
+}
+
+void GPS::setBaud(int baud)
+{
+    serial.baud(baud);
+    
+    return;
+}
+
+void GPS::setUpdateRate(int rate)
+{
+    char msg[10] = { 0xA0, 0xA1, 0x00, 0x03,
+                    0x0E, rate&0xFF, 01,
+                    0, 0x0D, 0x0A };
+    for (int i=4; i < 7; i++) {
+        msg[7] ^= msg[i];
+    }
+    switch (rate) {
+    case 1 :
+    case 2 :
+    case 4 :
+    case 5 :
+    case 8 :
+    case 10 :
+    case 20 :
+        for (int i=0; i < 10; i++)            
+            serial.putc(msg[i]);
+        break;
+    default :
+        break;
+    }
+}
+
+void GPS::setNmeaMessages(bool gga, bool gsa, bool gsv, bool gll, bool rmc, bool vtg)
+{
+    if (_type == VENUS) {
+        // VENUS Binary MsgID=0x08
+        // GGA interval
+        // GSA interval
+        // GSV interval
+        // GLL interval
+        // RMC interval
+        // VTG interval
+        // ZDA interval -- hardcode off
+        char msg[15] = { 0xA0, 0xA1, 0x00, 0x09, 
+                         0x08, gga, gsa, gsv, gll, rmc, vtg, 0,
+                         0, 0x0D, 0x0A };
+        for (int i=4; i < 12; i++) {
+            msg[12] ^= msg[i];
+        }
+        for (int i=0; i < 15; i++)
+            serial.putc(msg[i]);
+    }
+}
+    
+
+void GPS::gsvMessage(bool enable)
+{
+    if (enable) {
+        if (_type == MTK) {
+            serial.printf("$PSRF103,03,00,01,01*26\r\n");     // Enable GSV
+        } else if (_type == VENUS) {
+        }
+    } else {
+        if (_type == MTK) {
+            serial.printf("$PSRF103,03,00,00,01*27\r\n");     // Disable GSV
+        } else if (_type == VENUS) {
+            // ??
+        }
+    }
+
+    return;
+}
+
+void GPS::gsaMessage(bool enable)
+{
+    if (enable) {
+        if (_type == SIRF) {
+            serial.printf("$PSRF103,02,00,01,01*27\r\n");     // Enable GSA
+        } else if (_type == VENUS) {
+            // ??
+        }
+    } else {
+        if (_type == SIRF) {
+            serial.printf("$PSRF103,02,00,00,01*26\r\n");     // Disable GSA
+        } else if (_type == VENUS) {
+            // ??
+        }
+    }
+    
+    return;
+}
+
+
+// Handle data from a GPS (there may be two GPS's so needed to put the code in one routine
+//
+void GPS::process(GeoPosition &here, char *date, char *time)
+{
+    double lat, lon;
+    unsigned long age;
+    
+    nmea.reset_ready(); // reset the flags
+    //pc.printf("%d GPS RMC are ready\n", millis);
+    nmea.f_get_position(&lat, &lon, &age);
+    nmea.crack_datetime(&year, &month, &day, &hour, &minute, &second, &hundredths, &age);
+
+    sprintf(date, "%02d/%02d/%4d", month, day, year);
+    sprintf(time, "%02d:%02d:%02d.%03d", hour, minute, second, hundredths);
+
+    hdop = nmea.f_hdop();
+
+    // Bearing and distance to waypoint
+    here.set(lat, lon);
+
+    //pc.printf("HDOP: %.1f gyro: %d\n", gps1_hdop, gyro);
+
+    return;
+}
+
+
+void GPS::init()
+{    
+    // Initialize the GPS comm and handler
+    //serial.baud(57600); // LOCOSYS LS20031
+    //DigitalIn myRx(_rx);
+    //Timer tm;
+
+
+/*    
+    //pc.printf("gps.init()\n\n");
+    int rate = 99999999;
+    for (int i=0; i < 10; i++) {    
+        //pc.printf("rate: %d\n", rate);
+        while( myRx ); // wait for low
+        tm.reset();
+        tm.start();
+        while ( !myRx ); // wait for high
+        if (tm.read_us() < rate) rate = tm.read_us();
+    }
+*/
+    if (_type == MTK) {
+        gsvMessage(false);      // Disable GSV
+        gsaMessage(false);      // Disable GSA
+    } else if (_type == VENUS) {
+        setNmeaMessages(true, true, false, false, true, false);
+        setUpdateRate(10);
+    }
+    
+    // Synchronize with GPS
+    nmea.reset_ready();
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/GPS/GPS.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/GPS/GPS.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,45 @@
+// For SiRF III
+
+#ifndef __GPS_H
+#define __GPS_H
+
+/** GPS interface abstraction library */
+
+#include "mbed.h"
+#include "TinyGPS.h"
+#include "GeoPosition.h"
+
+#define SIRF 1
+#define MTK 2
+#define VENUS 3
+
+class GPS {
+public:
+    GPS(PinName tx, PinName rx, int type);
+    void setType(int type);
+    void setBaud(int baud);
+    void setUpdateRate(int rate);
+    void setNmeaMessages(bool gga, bool gsa, bool gsv, bool gll, bool rmc, bool vtg);
+    void gsvMessage(bool enable);
+    void gsaMessage(bool enable);
+    void process(GeoPosition &here, char *date, char *time);
+    void init(void);
+    void gpsStartCapture(void);
+    void gpsStopCapture(void);
+    void recv(void);
+    int year;           // gps date variables
+    byte month;
+    byte day;
+    byte hour;
+    byte minute;
+    byte second;
+    byte hundredths;
+    float hdop;         // gps horizontal dilution of precision
+    Serial serial;
+    TinyGPS nmea;
+private:
+    PinName _rx;
+    int _type;       // type of GPS device
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/GPS/TinyGPS/TinyGPS.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/GPS/TinyGPS/TinyGPS.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,341 @@
+/*
+  TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
+  Copyright (C) 2008-9 Mikal Hart
+  All rights reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+  
+  Ported to mbed by Michael Shimniok http://www.bot-thoughts.com/
+*/
+
+#include "TinyGPS.h"
+
+#define _GPRMC_TERM   "GPRMC"
+#define _GPGGA_TERM   "GPGGA"
+#define _GPGSV_TERM   "GPGSV"
+
+TinyGPS::TinyGPS()
+:  _time(GPS_INVALID_TIME)
+,  _date(GPS_INVALID_DATE)
+,  _latitude(GPS_INVALID_ANGLE)
+,  _longitude(GPS_INVALID_ANGLE)
+,  _altitude(GPS_INVALID_ALTITUDE)
+,  _speed(GPS_INVALID_SPEED)
+,  _course(GPS_INVALID_ANGLE)
+,  _hdop(0)
+,  _sat_count(0)
+,  _last_time_fix(GPS_INVALID_FIX_TIME)
+,  _last_position_fix(GPS_INVALID_FIX_TIME)
+,  _parity(0)
+,  _is_checksum_term(false)
+,  _sentence_type(_GPS_SENTENCE_OTHER)
+,  _term_number(0)
+,  _term_offset(0)
+,  _gps_data_good(false)
+,  _rmc_ready(false)
+,  _gga_ready(false)
+,  _gsv_ready(false)
+#ifndef _GPS_NO_STATS
+,  _encoded_characters(0)
+,  _good_sentences(0)
+,  _failed_checksum(0)
+#endif
+{
+  _term[0] = '\0';
+}
+
+//
+// public methods
+//
+
+bool TinyGPS::encode(char c)
+{
+  bool valid_sentence = false;
+
+  ++_encoded_characters;
+  switch(c)
+  {
+  case ',': // term terminators
+    _parity ^= c;
+  case '\r':
+  case '\n':
+  case '*':
+    if (_term_offset < sizeof(_term))
+    {
+      _term[_term_offset] = 0;
+      valid_sentence = term_complete();
+    }
+    ++_term_number;
+    _term_offset = 0;
+    _is_checksum_term = c == '*';
+    return valid_sentence;
+
+  case '$': // sentence begin
+    _term_number = _term_offset = 0;
+    _parity = 0;
+    _sentence_type = _GPS_SENTENCE_OTHER;
+    _is_checksum_term = false;
+    _gps_data_good = false;
+    return valid_sentence;
+  }
+
+  // ordinary characters
+  if (_term_offset < sizeof(_term) - 1)
+    _term[_term_offset++] = c;
+  if (!_is_checksum_term)
+    _parity ^= c;
+
+  return valid_sentence;
+}
+
+#ifndef _GPS_NO_STATS
+void TinyGPS::stats(unsigned long *chars, unsigned short *sentences, unsigned short *failed_cs)
+{
+  if (chars) *chars = _encoded_characters;
+  if (sentences) *sentences = _good_sentences;
+  if (failed_cs) *failed_cs = _failed_checksum;
+}
+#endif
+
+//
+// internal utilities
+//
+int TinyGPS::from_hex(char a) 
+{
+  if (a >= 'A' && a <= 'F')
+    return a - 'A' + 10;
+  else if (a >= 'a' && a <= 'f')
+    return a - 'a' + 10;
+  else
+    return a - '0';
+}
+
+int TinyGPS::parse_int()
+{
+  char *p = _term;
+  bool isneg = *p == '-';
+  if (isneg) ++p;
+  while (*p == '0') ++p;
+  int ret = gpsatol(p);
+  return isneg ? -ret : ret;
+}
+
+unsigned long TinyGPS::parse_decimal()
+{
+  char *p = _term;
+  bool isneg = *p == '-';
+  if (isneg) ++p;
+  unsigned long ret = 100UL * gpsatol(p);
+  while (gpsisdigit(*p)) ++p;
+  if (*p == '.')
+  {
+    if (gpsisdigit(p[1]))
+    {
+      ret += 10 * (p[1] - '0');
+      if (gpsisdigit(p[2]))
+        ret += p[2] - '0';
+    }
+  }
+  return isneg ? -ret : ret; // TODO:  can't return - when we're returning an unsigned!
+}
+
+// mes 04/27/12 increased fractional precision to 7 digits, was 5
+unsigned long TinyGPS::parse_degrees()
+{
+  char *p;
+  unsigned long left = gpsatol(_term);
+  unsigned long tenk_minutes = (left % 100UL) * 1000000UL;
+  for (p=_term; gpsisdigit(*p); ++p);
+  if (*p == '.')
+  {
+    unsigned long mult = 100000;
+    while (gpsisdigit(*++p))
+    {
+      tenk_minutes += mult * (*p - '0');
+      mult /= 10;
+    }
+  }
+  return (left / 100) * 10000000 + tenk_minutes / 6;
+}
+
+// Processes a just-completed term
+// Returns true if new sentence has just passed checksum test and is validated
+bool TinyGPS::term_complete()
+{
+    if (_is_checksum_term) {
+    
+        byte checksum = 16 * from_hex(_term[0]) + from_hex(_term[1]);
+        if (checksum == _parity) {
+        
+            if (_gps_data_good) {
+            
+#ifndef _GPS_NO_STATS
+            ++_good_sentences;
+#endif
+            _last_time_fix = _new_time_fix;
+            _last_position_fix = _new_position_fix;
+
+            switch(_sentence_type) {
+            case _GPS_SENTENCE_GPRMC:
+                _time      = _new_time;
+                _date      = _new_date;
+                _latitude  = _new_latitude;
+                _longitude = _new_longitude;
+                _speed     = _new_speed;
+                _course    = _new_course;
+                _rmc_ready = true;
+                break;
+            case _GPS_SENTENCE_GPGGA:
+                _altitude  = _new_altitude;
+                _time      = _new_time;
+                _latitude  = _new_latitude;
+                _longitude = _new_longitude;
+                _gga_ready = true;
+                _hdop      = _new_hdop;
+                _sat_count = _new_sat_count;
+            case _GPS_SENTENCE_GPGSV:
+                _gsv_ready = true;
+                break;
+            }
+
+            return true;
+        }
+    }
+
+#ifndef _GPS_NO_STATS
+    else
+        ++_failed_checksum;
+#endif
+    return false;
+    }
+
+    // the first term determines the sentence type
+    if (_term_number == 0) {
+        if (!gpsstrcmp(_term, _GPRMC_TERM))
+            _sentence_type = _GPS_SENTENCE_GPRMC;
+        else if (!gpsstrcmp(_term, _GPGGA_TERM))
+            _sentence_type = _GPS_SENTENCE_GPGGA;
+        else if (!gpsstrcmp(_term, _GPGSV_TERM))
+            _sentence_type = _GPS_SENTENCE_GPGSV;
+        else
+            _sentence_type = _GPS_SENTENCE_OTHER;
+        return false;
+    }
+
+    if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0])
+    /*
+    if (_sentence_type == _GPS_SENTENCE_GPGSV) {
+        // $GPGSV,3,1,12,05,54,069,45,12,44,061,44,21,07,184,46,22,78,289,47*72<CR><LF>
+        // TODO: need to maintain a list of 12 structs with sat info and update it each time
+        switch (_term_number) {
+        case 0 : // number of messages
+            break;
+        case 1 : // sequence number
+            break;
+        case 2 : // satellites in view 
+            break;
+        case 3 : // sat ID
+        case 8 :
+        case 12 :
+        case 16 :
+            break;
+        case 4 : // elevation
+        case 9 :
+        case 13 :
+        case 17 :
+            break;
+        case 5 : // azimuth
+        case 10 :
+        case 14 :
+        case 18 :
+            break;
+        case 6 : // SNR
+        case 11 :
+        case 15 :
+        case 19 :
+            break;
+        }
+    } else {*/
+        switch (((_sentence_type == _GPS_SENTENCE_GPGGA) ? 200 : 100) + _term_number) {
+        case 101: // Time in both sentences
+        case 201:
+          _new_time = parse_decimal();
+          _new_time_fix = millis();
+          break;
+        case 102: // GPRMC validity
+          _gps_data_good = _term[0] == 'A';
+          break;
+        case 103: // Latitude
+        case 202:
+          _new_latitude = parse_degrees();
+          _new_position_fix = millis();
+          break;
+        case 104: // N/S
+        case 203:
+          if (_term[0] == 'S')
+            _new_latitude = -_new_latitude;
+          break;
+        case 105: // Longitude
+        case 204:
+          _new_longitude = parse_degrees();
+          break;
+        case 106: // E/W
+        case 205:
+          if (_term[0] == 'W')
+            _new_longitude = -_new_longitude;
+          break;
+        case 107: // Speed (GPRMC)
+          _new_speed = parse_decimal();
+          break;
+        case 108: // Course (GPRMC)
+          _new_course = parse_decimal();
+          break;
+        case 109: // Date (GPRMC)
+          _new_date = gpsatol(_term);
+          break;
+        case 206: // Fix data (GPGGA)
+          _gps_data_good = _term[0] > '0';
+          break;
+        case 207: // Number of satelites tracked (GPGGA)
+          _new_sat_count = parse_int();
+          break;
+        case 208: // Horizontal Dilution of Position (GPGGA)
+          _new_hdop = parse_decimal();
+          break;
+        case 209: // Altitude (GPGGA)
+          _new_altitude = parse_decimal();
+          break;
+        default :
+          break;
+        } /* switch */
+    //}
+
+  return false;
+}
+
+long TinyGPS::gpsatol(const char *str)
+{
+  long ret = 0;
+  while (gpsisdigit(*str))
+    ret = 10 * ret + *str++ - '0';
+  return ret;
+}
+
+int TinyGPS::gpsstrcmp(const char *str1, const char *str2)
+{
+  while (*str1 && *str1 == *str2)
+    ++str1, ++str2;
+  return *str1;
+}
diff -r 000000000000 -r 826c6171fc1b Sensors/GPS/TinyGPS/TinyGPS.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/GPS/TinyGPS/TinyGPS.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,267 @@
+/*
+  TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
+  Copyright (C) 2008-9 Mikal Hart
+  All rights reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+  
+  Ported to mbed by Michael Shimniok
+*/
+
+#include "mbed.h"
+#include "types.h"
+
+#ifndef TinyGPS_h
+#define TinyGPS_h
+
+#define _GPS_VERSION 9 // software version of this library
+#define _GPS_MPH_PER_KNOT 1.15077945
+#define _GPS_MPS_PER_KNOT 0.51444444
+#define _GPS_KMPH_PER_KNOT 1.852
+#define _GPS_MILES_PER_METER 0.00062137112
+#define _GPS_KM_PER_METER 0.001
+//#define _GPS_NO_STATS
+
+/** TinyGPS - a small GPS library for Arduino providing basic NMEA parsing Copyright (C) 2008-9 Mikal Hart
+ * All rights reserved. Modified by Michael Shimniok 
+ */
+
+class TinyGPS
+{
+  public:
+  
+    /** Create a new GPS parsing object for parsing NMEA sentences
+     */
+    TinyGPS();
+    
+    /** Parse a single character received from GPS
+     *
+     * @param c is the character received from the GPS
+     * @returns true if processing ok
+     */
+    bool encode(char c);
+    
+    /** Shorthand operator for encode()
+     */
+    TinyGPS &operator << (char c) {encode(c); return *this;}
+    
+    /** Return lat/long in hundred thousandths of a degree and age of fix in milliseconds
+     * @returns latitude is the latitude of the most recent fix that was parsed
+     * @returns longitude is the longitude of the most recent fix that was parsed
+     * @returns fix_age is the age of the fix (if available from the NMEA sentences being parsed)
+     */
+    inline void get_position(long *latitude, long *longitude, unsigned long *fix_age = 0)
+    {
+      if (latitude) *latitude = _latitude;
+      if (longitude) *longitude = _longitude;
+      if (fix_age) *fix_age = _last_position_fix == GPS_INVALID_FIX_TIME ? 
+        GPS_INVALID_AGE : millis() - _last_position_fix;
+    }
+
+    /** Return the date and time from the parsed NMEA sentences
+     *
+     * @returns date as an integer value
+     * @returns time as an integer value
+     * @returns fix_age in milliseconds if available
+     */
+    inline void get_datetime(unsigned long *date, unsigned long *time, unsigned long *fix_age = 0)
+    {
+      if (date) *date = _date;
+      if (time) *time = _time;
+      if (fix_age) *fix_age = _last_time_fix == GPS_INVALID_FIX_TIME ? 
+        GPS_INVALID_AGE : millis() - _last_time_fix;
+    }
+
+    /** signed altitude in centimeters (from GPGGA sentence)
+     * @returns altitude in centimeters, integer
+     */
+    inline long altitude() { return _altitude; }
+
+    /** course in last full GPRMC sentence in 100th of a degree
+     * @returns course as an integer, 100ths of a degree
+     */
+    inline unsigned long course() { return _course; }
+    
+    /** speed in last full GPRMC sentence in 100ths of a knot
+     * @returns speed in 100ths of a knot
+     */
+    unsigned long speed() { return _speed; }
+
+    /* horizontal dilution of position in last full GPGGA sentence in 100ths
+     * @returns hdop in 100ths
+     */
+    unsigned long hdop() { return _hdop; }
+
+    /** number of satellites tracked in last full GPGGA sentence
+     * @returns number of satellites tracked 
+     */
+    unsigned long sat_count() { return _sat_count; }
+
+#ifndef _GPS_NO_STATS
+    void stats(unsigned long *chars, unsigned short *good_sentences, unsigned short *failed_cs);
+#endif
+
+    /** returns position as double precision
+     *
+     * @returns latitude as double precision
+     * @returns longitude as double precision
+     * @returns fix age in milliseconds if available
+     */
+    inline void f_get_position(double *latitude, double *longitude, unsigned long *fix_age = 0)
+    {
+      long lat, lon;
+      get_position(&lat, &lon, fix_age);
+      // mes 04/27/12 increased fractional precision to 7 digits, was 5
+      *latitude = lat / 10000000.0;
+      *longitude = lon / 10000000.0;
+    }
+
+    /** Convert date and time of last parsed sentence to integers
+     *
+     * @returns year
+     * @returns month
+     * @returns day of month
+     * @returns hour
+     * @returns minute
+     * @returns second
+     * @returns hundreths
+     * @returns fix_age in milliseconds if available
+     */
+    inline void crack_datetime(int *year, byte *month, byte *day, 
+      byte *hour, byte *minute, byte *second, byte *hundredths = 0, unsigned long *fix_age = 0)
+    {
+      unsigned long date, time;
+      get_datetime(&date, &time, fix_age);
+      if (year) 
+      {
+        *year = date % 100;
+        *year += *year > 80 ? 1900 : 2000;
+      }
+      if (month) *month = (date / 100) % 100;
+      if (day) *day = date / 10000;
+      if (hour) *hour = time / 1000000;
+      if (minute) *minute = (time / 10000) % 100;
+      if (second) *second = (time / 100) % 100;
+      if (hundredths) *hundredths = time % 100;
+    }
+
+    /** returns altitude as a float
+    */
+    inline double f_altitude()    { return altitude() / 100.0; }
+    
+    /** returns course as a float
+    */
+    inline double f_course()      { return course() / 100.0; }
+    
+    /** returns speed in knots as a float
+    */
+    inline double f_speed_knots() { return speed() / 100.0; }
+    
+    /** returns speed in mph as a float 
+    */
+    inline double f_speed_mph()   { return _GPS_MPH_PER_KNOT * f_speed_knots(); }
+    
+    /** returns speed in meters per second as a float
+    */
+    inline double f_speed_mps()   { return _GPS_MPS_PER_KNOT * f_speed_knots(); }
+    
+    /** returns speed in km per hour as a float
+    */
+    inline double f_speed_kmph()  { return _GPS_KMPH_PER_KNOT * f_speed_knots(); }
+    
+    /** returns hdop as a float
+    */
+    inline double f_hdop()      { return hdop() / 100.0; }
+
+    /** @returns library version
+    */
+    static int library_version() { return _GPS_VERSION; }
+
+    /** determine if RMC sentence parsed since last reset_ready()
+     */
+    inline bool rmc_ready() { return _rmc_ready; }
+
+    /** determine if GGA sentence parsed since last reset_ready()
+     */
+    inline bool gga_ready() { return _gga_ready; }
+
+    /** determine if GSV sentence parsed since last reset_ready()
+     */
+    inline bool gsv_ready() { return _gsv_ready; }
+    
+    /** Reset the ready flags for all the parsed sentences
+     */
+    inline void reset_ready() { _gsv_ready = _rmc_ready = _gga_ready = false; }
+
+    enum {GPS_INVALID_AGE = 0xFFFFFFFF, GPS_INVALID_ANGLE = 999999999, GPS_INVALID_ALTITUDE = 999999999, GPS_INVALID_DATE = 0,
+      GPS_INVALID_TIME = 0xFFFFFFFF, GPS_INVALID_SPEED = 999999999, GPS_INVALID_FIX_TIME = 0xFFFFFFFF};
+
+private:
+    enum {_GPS_SENTENCE_GPGGA, _GPS_SENTENCE_GPRMC, _GPS_SENTENCE_GPGSV, _GPS_SENTENCE_OTHER};
+    
+    // properties
+    unsigned long _time, _new_time;
+    unsigned long _date, _new_date;
+    long _latitude, _new_latitude;
+    long _longitude, _new_longitude;
+    long _altitude, _new_altitude;
+    unsigned long  _speed, _new_speed;
+    unsigned long  _course, _new_course;
+    unsigned long  _hdop, _new_hdop;
+    unsigned int _sat_count, _new_sat_count;
+    unsigned long _last_time_fix, _new_time_fix;
+    unsigned long _last_position_fix, _new_position_fix;
+
+    // parsing state variables
+    byte _parity;
+    bool _is_checksum_term;
+    char _term[15];
+    byte _sentence_type;
+    byte _term_number;
+    byte _term_offset;
+    bool _gps_data_good;
+    bool _rmc_ready;
+    bool _gga_ready;
+    bool _gsv_ready;
+
+#ifndef _GPS_NO_STATS
+    // statistics
+    unsigned long _encoded_characters;
+    unsigned short _good_sentences;
+    unsigned short _failed_checksum;
+    unsigned short _passed_checksum;
+#endif
+
+    // internal utilities
+    int from_hex(char a);
+    int parse_int();
+    unsigned long parse_decimal();
+    unsigned long parse_degrees();
+    bool term_complete();
+    bool gpsisdigit(char c) { return c >= '0' && c <= '9'; }
+    long gpsatol(const char *str);
+    int gpsstrcmp(const char *str1, const char *str2);
+};
+
+// Arduino 0012 workaround
+#undef int
+#undef char
+#undef long
+#undef byte
+#undef double
+#undef abs
+#undef round 
+
+#endif
diff -r 000000000000 -r 826c6171fc1b Sensors/GPS/TinyGPS/types.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/GPS/TinyGPS/types.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,7 @@
+#ifndef __TYPES_H
+#define __TYPES_H
+
+typedef char byte;
+typedef int millis;
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/HMC5843/HMC5843.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/HMC5843/HMC5843.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,222 @@
+/**
+ * @author Jose R. Padron
+ * @author Used HMC6352 library  developed by Aaron Berk as template
+ * @section LICENSE
+ *
+ * Copyright (c) 2010 ARM Limited
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * @section DESCRIPTION
+ *
+ * Honeywell HMC5843digital compass.
+ *
+ * Datasheet:
+ *
+ * http://www.ssec.honeywell.com/magnetic/datasheets/HMC5843.pdf
+ */
+
+/**
+ * Includes
+ */
+#include "HMC5843.h"
+
+HMC5843::HMC5843(PinName sda, PinName scl) 
+{
+    i2c_ = new I2C(sda, scl);
+    //100KHz, as specified by the datasheet.
+    i2c_->frequency(100000);
+    setOpMode(HMC5843_CONTINUOUS, HMC5843_10HZ_NORMAL, HMC5843_1_0GA);
+
+    return;
+}
+
+
+void HMC5843::setOffset(float x, float y, float z)
+{
+    return;
+}
+
+
+void HMC5843::setScale(float x, float y, float z)
+{
+    return;
+}
+     
+
+void HMC5843::setSleepMode()
+{
+    write(HMC5843_MODE, HMC5843_SLEEP);
+
+    return;
+}
+
+
+void HMC5843::setDefault(void)
+{
+   write(HMC5843_CONFIG_A,HMC5843_10HZ_NORMAL);
+   write(HMC5843_CONFIG_B,HMC5843_1_0GA);
+   write(HMC5843_MODE,HMC5843_CONTINUOUS);
+   wait_ms(100);
+   
+   return;
+}
+
+
+void HMC5843::setOpMode(int mode, int ConfigA, int ConfigB)
+{      
+    write(HMC5843_CONFIG_A,ConfigA);
+    write(HMC5843_CONFIG_B,ConfigB);
+    write(HMC5843_MODE,mode);
+    
+    return;
+}
+
+
+void HMC5843::write(int address, int data)
+{
+    char tx[2];
+   
+    tx[0]=address;
+    tx[1]=data;
+
+    i2c_->write(HMC5843_I2C_WRITE,tx,2);
+   
+    wait_ms(100);
+
+    return;
+}
+
+
+void HMC5843::read(int m[3])
+{
+    readData(m);
+
+    return;
+}
+
+void HMC5843::readMag(int m[3])
+{
+    readData(m);
+
+    return;
+}
+
+void HMC5843::readData(int readings[3])
+{
+    char tx[1];
+    char rx[2];
+    
+    
+    tx[0]=HMC5843_X_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    readings[0]= (short)(rx[0]<<8|rx[1]);
+
+     
+    tx[0]=HMC5843_Y_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    readings[1]= (short) (rx[0]<<8|rx[1]);
+     
+    tx[0]=HMC5843_Z_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    readings[2]= (short) (rx[0]<<8|rx[1]);
+    
+    return;
+}
+
+int HMC5843::getMx()
+{
+    char tx[1];
+    char rx[2];
+    
+    
+    tx[0]=HMC5843_X_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    
+    return (short) rx[0]<<8|rx[1];
+}
+
+int HMC5843::getMy() 
+{
+    char tx[1];
+    char rx[2];
+    
+    
+    tx[0]=HMC5843_Y_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    
+    return (short) rx[0]<<8|rx[1];
+}
+
+
+int HMC5843::getMz(){
+
+    char tx[1];
+    char rx[2];
+    
+    
+    tx[0]=HMC5843_Z_MSB;
+    i2c_->write(HMC5843_I2C_READ,tx,1);
+    i2c_->read(HMC5843_I2C_READ,rx,2);
+    
+    return (short) rx[0]<<8|rx[1];
+}
+
+
+int HMC5843::getStatus(void)
+{
+    return 0;
+}
+
+
+void HMC5843::getAddress(char *buffer)
+{    
+   char rx[3];
+   char tx[1];
+   tx[0]=HMC5843_IDENT_A;
+    
+       
+    i2c_->write(HMC5843_I2C_WRITE, tx,1);
+   
+    wait_ms(1);
+    
+    i2c_->read(HMC5843_I2C_READ,rx,3);
+    
+    buffer[0]=rx[0];
+    buffer[1]=rx[1];
+    buffer[2]=rx[2];
+    
+    return;
+}
+
+     
+void HMC5843::frequency(int hz)
+{
+    if (hz == 100000)
+        i2c_->frequency(100000);
+    else if (hz == 400000)
+        i2c_->frequency(400000);
+
+    return;
+}
diff -r 000000000000 -r 826c6171fc1b Sensors/HMC5843/HMC5843.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/HMC5843/HMC5843.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,280 @@
+/**
+ * @author Uwe Gartmann
+ * @author Used HMC5843 library developed by Jose R. Padron and Aaron Berk as template
+ *
+ * @section LICENSE
+ *
+ * Copyright (c) 2010 ARM Limited
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * @section DESCRIPTION
+ *
+ * Honeywell HMC5843 digital compass.
+ *
+ * Datasheet:
+ *
+ * http://www.ssec.honeywell.com/magnetic/datasheets/HMC5843.pdf
+ */
+
+#ifndef HMC5843_H
+#define HMC5843_H
+
+#include "mbed.h"
+
+#define HMC5843_I2C_ADDRESS 0x1E //7-bit address. 0x3C write, 0x3D read.
+#define HMC5843_I2C_WRITE   0x3C 
+#define HMC5843_I2C_READ    0x3D 
+
+//Values Config A
+#define HMC5843_0_5HZ_NORMAL         0x00
+#define HMC5843_0_5HZ_POSITIVE       0x01
+#define HMC5843_0_5HZ_NEGATIVE       0x02
+
+#define HMC5843_1HZ_NORMAL           0x04
+#define HMC5843_1HZ_POSITIVE         0x05
+#define HMC5843_1HZ_NEGATIVE         0x06
+
+#define HMC5843_2HZ_NORMAL           0x08
+#define HMC5843_2HZ_POSITIVE         0x09
+#define HMC5843_2HZ_NEGATIVE         0x0A
+
+#define HMC5843_5HZ_NORMAL           0x0C
+#define HMC5843_5HZ_POSITIVE         0x0D
+#define HMC5843_5HZ_NEGATIVE         0x0E
+
+#define HMC5843_10HZ_NORMAL           0x10
+#define HMC5843_10HZ_POSITIVE         0x11
+#define HMC5843_10HZ_NEGATIVE         0x12
+
+#define HMC5843_20HZ_NORMAL           0x14
+#define HMC5843_20HZ_POSITIVE         0x15
+#define HMC5843_20HZ_NEGATIVE         0x16
+
+#define HMC5843_50HZ_NORMAL           0x18
+#define HMC5843_50HZ_POSITIVE         0x19
+#define HMC5843_50HZ_NEGATIVE         0x1A
+
+//Values Config B
+#define HMC5843_0_7GA         0x00
+#define HMC5843_1_0GA         0x20
+#define HMC5843_1_5GA         0x40
+#define HMC5843_2_0GA         0x60
+#define HMC5843_3_2GA         0x80
+#define HMC5843_3_8GA         0xA0
+#define HMC5843_4_5GA         0xC0
+#define HMC5843_6_5GA         0xE0
+
+//Values MODE
+#define HMC5843_CONTINUOUS   0x00
+#define HMC5843_SINGLE       0x01
+#define HMC5843_IDLE         0x02
+#define HMC5843_SLEEP        0x03
+
+
+
+#define HMC5843_CONFIG_A     0x00
+#define HMC5843_CONFIG_B     0x01
+#define HMC5843_MODE         0x02
+#define HMC5843_X_MSB        0x03
+#define HMC5843_X_LSB        0x04
+#define HMC5843_Y_MSB        0x05
+#define HMC5843_Y_LSB        0x06
+#define HMC5843_Z_MSB        0x07
+#define HMC5843_Z_LSB        0x08
+#define HMC5843_STATUS       0x09
+#define HMC5843_IDENT_A      0x0A
+#define HMC5843_IDENT_B      0x0B
+#define HMC5843_IDENT_C      0x0C
+
+
+
+/**
+ * Interface library for the Honeywell HMC5843 digital compass.
+ * @author Michael Shimniok http://www.bot-thoughts.com/
+ * @author Based on library by Uwe Gartmann
+ * @author In turn based on HMC5843 library developed by Jose R. Padron and Aaron Berk as template
+ *
+ * This version is modified to follow the same member functions of my LSM303DLH library. The intent
+ * is to make it drop in compatible with my other magnetometer libraries.  For now, setScale() and
+ * setOffset() have no effect at this time.
+ *
+ * @code
+ * #include "mbed.h"
+ * #include "HMC5843.h"
+ *
+ * HMC5843 compass(p28, p27);
+ * ...
+ * int m[3];
+ * ...
+ * compass.readMag(m);
+ *
+ * @endcode
+ */
+class HMC5843 {
+
+public:
+
+    /**
+     * Create a new interface for an HMC5843.
+     *
+     * @param sda mbed pin to use for SDA line of I2C interface.
+     * @param scl mbed pin to use for SCL line of I2C interface.
+     */
+    HMC5843(PinName sda, PinName scl);
+
+
+   /** sets the x, y, and z offset corrections for hard iron calibration
+    * 
+    * Calibration details here:
+    *  http://mbed.org/users/shimniok/notebook/quick-and-dirty-3d-compass-calibration/
+    *
+    * If you gather raw magnetometer data and find, for example, x is offset
+    * by hard iron by -20 then pass +20 to this member function to correct
+    * for hard iron.
+    *
+    * @param x is the offset correction for the x axis
+    * @param y is the offset correction for the y axis
+    * @param z is the offset correction for the z axis
+    */
+    void setOffset(float x, float y, float z);
+
+
+    /** sets the scale factor for the x, y, and z axes
+     *
+     * Calibratio details here:
+     *  http://mbed.org/users/shimniok/notebook/quick-and-dirty-3d-compass-calibration/
+     *
+     * Sensitivity of the three axes is never perfectly identical and this
+     * function can help to correct differences in sensitivity.  You're
+     * supplying a multipler such that x, y and z will be normalized to the
+     * same max/min values
+     */
+    void setScale(float x, float y, float z);
+
+        
+    /**
+     * Enter into sleep mode.
+     */
+    void setSleepMode();
+    
+       
+    /**
+     * Set Device in Default Mode.
+     * HMC5843_CONTINUOUS, HMC5843_10HZ_NORMAL HMC5843_1_0GA
+     */
+    void setDefault();
+
+       
+    /**
+     * Set the operation mode.
+     *
+     * @param mode 0x00 -> Continuous
+     *             0x01 -> Single
+     *             0x02 -> Idle
+     * @param ConfigA values
+     * @param ConfigB values
+     */
+    void setOpMode(int mode, int ConfigA, int ConfigB);
+
+    
+    /**
+     * Write to a register on the device.
+     *
+     * @param address is the register address to be written.
+     * @param data is the data to write.
+     */
+    void write(int address, int data);
+
+
+    /** read the calibrated accelerometer and magnetometer values
+     *
+     * @param m is the magnetometer 3d vector, written by the function
+     */
+     void read(int m[3]);
+
+
+     /** read the calibrated magnetometer values
+      *
+      * @param m is the magnetometer 3d vector, written by the function
+      */
+     void readMag(int m[3]);
+
+
+     /**
+     * Get the output of all three axes.
+     *
+     * @param Pointer to a buffer to hold the magnetics value for the
+     *        x-axis, y-axis and z-axis [in that order].
+     */
+    void readData(int* readings);
+
+    
+    /**
+     * Get the output of X axis.
+     *
+     * @return x-axis magnetic value
+     */
+    int getMx();
+
+    
+    /**
+     * Get the output of Y axis.
+     *
+     * @return y-axis magnetic value
+     */
+    int getMy();
+
+    
+    /**
+     * Get the output of Z axis.
+     *
+     * @return z-axis magnetic value
+     */
+    int getMz();
+   
+    /**
+     * Get the current operation mode.
+     *
+     * @return Status register values
+     */
+    int getStatus(void);
+
+
+    /**
+     * Read the memory location on the device which contains the address.
+     *
+     * @param Pointer to a buffer to hold the address value
+     * Expected     H, 4 and 3.
+     */
+    void getAddress(char * address);
+
+    
+    /** sets the I2C bus frequency
+     *
+     * @param frequency is the I2C bus/clock frequency, either standard (100000) or fast (400000)
+     */
+    void frequency(int hz);
+
+private:
+    I2C* i2c_;
+
+};
+
+#endif /* HMC5843_H */
diff -r 000000000000 -r 826c6171fc1b Sensors/IncrementalEncoder/IncrementalEncoder.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/IncrementalEncoder/IncrementalEncoder.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,65 @@
+#include "IncrementalEncoder.h"
+
+IncrementalEncoder::IncrementalEncoder(PinName pin):  _lastTicks(0),  _ticks(0), _new(false), _interrupt(pin) {
+    _interrupt.mode(PullNone); // default is pulldown but my encoder board uses a pull-up and that just don't work
+    _interrupt.rise(this, &IncrementalEncoder::_incRise); 
+    _interrupt.fall(this, &IncrementalEncoder::_incFall); 
+    _t.start();
+    _t.reset();
+    _lastTime = _t.read_us();
+}
+
+unsigned int IncrementalEncoder::read() {
+// disable interrupts?
+    unsigned int ticks = _ticks - _lastTicks;
+    _lastTicks = _ticks;
+    _new=false;
+    return ticks;
+}  
+
+unsigned int IncrementalEncoder::readTotal() {
+    _new=false;
+    return _ticks;
+}
+
+unsigned int IncrementalEncoder::readRise() {
+    _new=false;
+    return _rise;
+}  
+
+unsigned int IncrementalEncoder::readFall() {
+    _new=false;
+    return _fall;
+}
+    
+unsigned int IncrementalEncoder::readTime() {
+    return _time;
+}
+    
+void IncrementalEncoder::reset() {
+    _ticks = _lastTicks = 0;
+}  
+
+void IncrementalEncoder::_increment() {
+    _ticks++;
+}
+
+#define A 0.3 // mix in how much from previous readings?
+void IncrementalEncoder::_incRise() {
+    _rise++;
+    _ticks++;
+    _new=true;
+    // compute time between ticks; only do this for rise
+    // to eliminate jitter
+    int now = _t.read_us();
+    _time = A*_time + (1-A)*(now - _lastTime);
+    // Dead band: if _time > xxxx then turn off and wait until next tick
+    // to start up again
+    _lastTime = now;
+}
+
+void IncrementalEncoder::_incFall() {
+    _fall++;
+    _ticks++;
+    _new=true;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/IncrementalEncoder/IncrementalEncoder.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/IncrementalEncoder/IncrementalEncoder.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,67 @@
+#ifndef __INCREMENTALENCODER_H
+#define __INCREMENTALENCODER_H
+
+#include "mbed.h"
+
+/** An interface for a simple, 1-track, incremental encoder. If using a simple reflectance sensor, then a voltage comparator
+ *  circuit will be required to generate the pulsetrain.  See: http://www.bot-thoughts.com/2011/03/avc-bot-wheel-encoders.html
+ *
+ */
+class IncrementalEncoder
+{
+    public:
+        /** Create an incremental encoder interface.  Increments counter at every rise and fall signal 
+         *
+         * @param pin -- the pin to which a digital pulsetrain is sent
+         */
+        IncrementalEncoder(PinName pin);
+
+        /** Get ticks since last call
+         *
+         * @returns the number of ticks since the last call to this method
+         */        
+        unsigned int read();
+
+        /** Get total tick count since last reset
+         *
+         * @returns total ticks since the last reset or instantiation
+         */
+        unsigned int readTotal();
+       
+        /** Get total rise tick count
+         *
+         * @returns total rise ticks
+         */
+        unsigned int readRise();
+
+        /** Get total fall tick count
+         *
+         * @returns total fall ticks
+         */
+        unsigned int readFall();
+
+        /** Read time interval between ticks
+         *
+         * @returns filtered time between encoder pulses
+         */
+        unsigned int readTime();
+       
+        /** Reset the tick counter
+         *
+         */
+        void reset();
+
+    private:
+        Timer _t;
+        unsigned int _lastTime;
+        unsigned int _time;
+        unsigned int _lastTicks;
+        unsigned int _ticks, _rise, _fall;
+        bool _new;
+        InterruptIn _interrupt;
+        void _increment();
+        void _incRise();
+        void _incFall();
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/L3G4200D/L3G4200D.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/L3G4200D/L3G4200D.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,103 @@
+/**
+ * Copyright (c) 2011 Pololu Corporation.  For more information, see
+ * 
+ * http://www.pololu.com/
+ * http://forum.pololu.com/
+ * 
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use,
+ * copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the
+ * Software is furnished to do so, subject to the following
+ * conditions:
+ * 
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ * 
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
+ * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
+ * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
+ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
+ * OTHER DEALINGS IN THE SOFTWARE.
+ */
+ 
+#include "mbed.h"
+#include <L3G4200D.h>
+#include <math.h>
+
+// Defines ////////////////////////////////////////////////////////////////
+
+// The Arduino two-wire interface uses a 7-bit number for the address, 
+// and sets the last bit correctly based on reads and writes
+// mbed I2C libraries take the 7-bit address shifted left 1 bit
+// #define GYR_ADDRESS (0xD2 >> 1)
+#define GYR_ADDRESS 0xD2
+
+// Public Methods //////////////////////////////////////////////////////////////
+
+// Constructor
+L3G4200D::L3G4200D(PinName sda, PinName scl):
+    _device(sda, scl)
+{
+    _device.frequency(400000);
+    // Turns on the L3G4200D's gyro and places it in normal mode.
+    // 0x0F = 0b00001111
+    // Normal power mode, all axes enabled
+    writeReg(L3G4200D_CTRL_REG1, 0x0F);
+    writeReg(L3G4200D_CTRL_REG4, 0x20); // 2000 dps full scale
+
+}
+
+// Writes a gyro register
+void L3G4200D::writeReg(byte reg, byte value)
+{
+    data[0] = reg;
+    data[1] = value;
+    
+    _device.write(GYR_ADDRESS, data, 2);
+}
+
+// Reads a gyro register
+byte L3G4200D::readReg(byte reg)
+{
+    byte value = 0;
+    
+    _device.write(GYR_ADDRESS, &reg, 1);
+    _device.read(GYR_ADDRESS, &value, 1);
+
+    return value;
+}
+
+// Reads the 3 gyro channels and stores them in vector g
+void L3G4200D::read(int g[3])
+{
+    // assert the MSB of the address to get the gyro 
+    // to do slave-transmit subaddress updating.
+    data[0] = L3G4200D_OUT_X_L | (1 << 7);
+    _device.write(GYR_ADDRESS, data, 1); 
+
+//    Wire.requestFrom(GYR_ADDRESS, 6);
+//    while (Wire.available() < 6);
+    
+    _device.read(GYR_ADDRESS, data, 6); 
+
+    uint8_t xla = data[0];
+    uint8_t xha = data[1];
+    uint8_t yla = data[2];
+    uint8_t yha = data[3];
+    uint8_t zla = data[4];
+    uint8_t zha = data[5];
+
+    g[0] = (short) (xha << 8 | xla);
+    g[1] = (short) (yha << 8 | yla);
+    g[2] = (short) (zha << 8 | zla);
+}
+
+byte L3G4200D::readTemp(void) {
+    return readReg(L3G4200D_OUT_TEMP);
+}
diff -r 000000000000 -r 826c6171fc1b Sensors/L3G4200D/L3G4200D.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/L3G4200D/L3G4200D.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,111 @@
+/* Copyright (c) 2011 Pololu Corporation.  For more information, see
+ * 
+ * http://www.pololu.com/
+ * http://forum.pololu.com/
+ * 
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use,
+ * copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the
+ * Software is furnished to do so, subject to the following
+ * conditions:
+ * 
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ * 
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
+ * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
+ * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
+ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
+ * OTHER DEALINGS IN THE SOFTWARE.
+ */
+
+#ifndef __L3G4200D_H
+#define __L3G4200D_H
+
+#include "mbed.h"
+
+// register addresses
+
+#define L3G4200D_WHO_AM_I      0x0F
+
+#define L3G4200D_CTRL_REG1     0x20
+#define L3G4200D_CTRL_REG2     0x21
+#define L3G4200D_CTRL_REG3     0x22
+#define L3G4200D_CTRL_REG4     0x23
+#define L3G4200D_CTRL_REG5     0x24
+#define L3G4200D_REFERENCE     0x25
+#define L3G4200D_OUT_TEMP      0x26
+#define L3G4200D_STATUS_REG    0x27
+
+#define L3G4200D_OUT_X_L       0x28
+#define L3G4200D_OUT_X_H       0x29
+#define L3G4200D_OUT_Y_L       0x2A
+#define L3G4200D_OUT_Y_H       0x2B
+#define L3G4200D_OUT_Z_L       0x2C
+#define L3G4200D_OUT_Z_H       0x2D
+
+#define L3G4200D_FIFO_CTRL_REG 0x2E
+#define L3G4200D_FIFO_SRC_REG  0x2F
+
+#define L3G4200D_INT1_CFG      0x30
+#define L3G4200D_INT1_SRC      0x31
+#define L3G4200D_INT1_THS_XH   0x32
+#define L3G4200D_INT1_THS_XL   0x33
+#define L3G4200D_INT1_THS_YH   0x34
+#define L3G4200D_INT1_THS_YL   0x35
+#define L3G4200D_INT1_THS_ZH   0x36
+#define L3G4200D_INT1_THS_ZL   0x37
+#define L3G4200D_INT1_DURATION 0x38
+
+typedef char byte;
+
+/** Interface library for the ST L3G4200D 3-axis gyro
+ *
+ * Ported from Pololu L3G4200D library for Arduino by
+ * Michael Shimniok http://bot-thoughts.com
+ *
+ * @code
+ * #include "mbed.h"
+ * #include "L3G4200D.h"
+ * L3G4200D gyro(p28, p27);
+ * ...
+ * int g[3];
+ * gyro.read(g);
+ * @endcode
+ */
+class L3G4200D
+{
+    public:
+        /** Create a new L3G4200D I2C interface
+         * @param sda is the pin for the I2C SDA line
+         * @param scl is the pin for the I2C SCL line
+         */
+        L3G4200D(PinName sda, PinName scl);
+        
+        /** Read gyro values
+         * @param g Array containing x, y, and z gyro values
+         * @return g Array containing x, y, and z gyro values
+         */
+        void read(int g[3]);
+
+        /** Read raw temperature value
+         * @return temperature value in raw byte form
+         */
+        byte readTemp(void);
+
+    private:
+        byte data[6];
+        int _rates[3];
+        I2C _device;
+        void writeReg(byte reg, byte value);
+        byte readReg(byte reg);
+        void enableDefault(void);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Sensors/LSM303DLM.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/LSM303DLM.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/shimniok/code/LSM303DLM/#0fcea8569714
diff -r 000000000000 -r 826c6171fc1b Sensors/Sensors.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/Sensors.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,416 @@
+/*
+
+MinIMU-9-Arduino-AHRS
+Pololu MinIMU-9 + Arduino AHRS (Attitude and Heading Reference System)
+
+Copyright (c) 2011 Pololu Corporation.
+http://www.pololu.com/
+
+MinIMU-9-Arduino-AHRS is based on sf9domahrs by Doug Weibel and Jose Julio:
+http://code.google.com/p/sf9domahrs/
+
+sf9domahrs is based on ArduIMU v1.5 by Jordi Munoz and William Premerlani, Jose
+Julio and Doug Weibel:
+http://code.google.com/p/ardu-imu/
+
+MinIMU-9-Arduino-AHRS is free software: you can redistribute it and/or modify it
+under the terms of the GNU Lesser General Public License as published by the
+Free Software Foundation, either version 3 of the License, or (at your option)
+any later version.
+
+MinIMU-9-Arduino-AHRS is distributed in the hope that it will be useful, but
+WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for
+more details.
+
+You should have received a copy of the GNU Lesser General Public License along
+with MinIMU-9-Arduino-AHRS. If not, see <http://www.gnu.org/licenses/>.
+
+*/
+
+#include "Sensors.h"
+#include "debug.h"
+#include "stdio.h"
+
+#define GYRO_SCALE 14.49787 // TODO: is the sign right here?? yes, see g_sign
+
+#define VFF 50.0 // voltage filter factor
+
+///////////////////// MAGNETOMETER CALIBRATION
+
+Sensors::Sensors():
+    _voltage(p19),               // Voltage from sensor board
+    _current(p20),               // Current from sensor board
+    _left(p30),                  // left wheel encoder
+    _right(p29),                 // Right wheel encoder
+    _gyro(p28, p27),             // MinIMU-9 gyro
+    _compass(p28, p27),          // MinIMU-9 compass/accelerometer
+    _rangers(p28, p27),          // Arduino ADC to I2C
+    _cam(p28, p27)
+{
+    for (int i=0; i < 3; i++) {
+        m_offset[i] = 0;
+        m_scale[i] = 1;
+    }
+
+    // TODO: parameterize
+    g_scale[0] = 1;
+    g_scale[1] = 1;
+    g_scale[2] = GYRO_SCALE;
+
+    g_sign[0] = 1;
+    g_sign[1] = -1;
+    g_sign[2] = -1;
+
+    a_sign[0] = -1;
+    a_sign[1] = 1;
+    a_sign[2] = 1;
+
+    m_sign[0] = 1;
+    m_sign[1] = -1;
+    m_sign[2] = -1;
+
+    // upside down mounting
+    //g_sign[3] = {1,1,1};        
+    //a_sign[3] = {-1,-1,-1};
+    //m_sign[3] = {1,1,1}; 
+}
+
+/* Compass_Calibrate
+ *
+ * Set the offset and scale calibration for the compass
+ */
+void Sensors::Compass_Calibrate(float offset[3], float scale[3])
+{
+    for (int i=0; i < 3; i++) {
+        m_offset[i] = offset[i];
+        m_scale[i] = scale[i];
+    }    
+ 
+    return;
+}
+
+
+void Sensors::Read_Encoders()
+{
+    // Odometry            
+    leftCount = _left.read();
+    rightCount = _right.read();
+    leftTotal += leftCount;
+    rightTotal += rightCount;
+            
+    // TODO--> sanity check on encoders; if difference between them
+    //  is huge, what do we do?  Slipping wheel?  Skidding wheel?
+    //  front encoders would be ideal as additional sanity check
+    
+    // TODO: move this into scheduler??
+    
+    // TODO: how do we track distance, should we only check distance everytime we do a nav/pos update?
+    // TODO: get rid of state variable
+    lrEncDistance  = (WHEEL_CIRC / WHEEL_STRIPES) * (double) leftCount;
+    rrEncDistance = (WHEEL_CIRC / WHEEL_STRIPES) * (double) rightCount;
+    encDistance = (lrEncDistance + rrEncDistance) / 2.0;
+    // compute speed from time between ticks
+    int leftTime = _left.readTime();
+    int rightTime = _right.readTime();
+
+    // We could also supplement this with distance/time calcs once we get up to a higher
+    // speed and encoder quantization error is lower
+    // To reduce asymmetry of the encoder operation, we're only reading time
+    // between rising ticks. So that means half the wheel stripes
+
+    if (leftTime <= 0) {
+        lrEncSpeed = 0;
+    } else {
+        lrEncSpeed = (2.0 * WHEEL_CIRC / WHEEL_STRIPES) / ((float) leftTime * 1e-6);
+    }
+    
+    if (rightTime <= 0) {
+        rrEncSpeed = 0;
+    } else {
+        rrEncSpeed = (2.0 * WHEEL_CIRC / WHEEL_STRIPES) / ((float) rightTime * 1e-6);
+    }
+        
+    // Dead band
+    if (lrEncSpeed < 0.1) lrEncSpeed = 0;
+    if (rrEncSpeed < 0.1) rrEncSpeed = 0;
+    // TODO: 3 use more sophisticated approach where we count if any ticks have happened lately
+    // and if not, reset the speed
+    encSpeed = (lrEncSpeed + rrEncSpeed) / 2.0;
+}
+
+
+void Sensors::Read_Gyro()
+{
+    _gyro.read(g);
+    gTemp = (int) _gyro.readTemp();
+    
+    gyro[_x_] = g_sign[_x_] * (g[_x_] - g_offset[_x_]); // really need to scale this too
+    gyro[_y_] = g_sign[_y_] * (g[_y_] - g_offset[_y_]); // really need to scale this too
+    gyro[_z_] = (g_sign[_z_] * (g[_z_] - g_offset[_z_])) / g_scale[_z_];
+
+    return;
+}
+
+// Reads x,y and z accelerometer registers
+void Sensors::Read_Accel()
+{
+    _compass.readAcc(a);
+
+    accel[_x_] = a_sign[_x_] * (a[_x_] - a_offset[_x_]);
+    accel[_y_] = a_sign[_y_] * (a[_y_] - a_offset[_y_]);
+    accel[_z_] = a_sign[_z_] * (a[_z_] - a_offset[_z_]);
+
+    return;  
+}
+
+void Sensors::Read_Compass()
+{
+    _compass.readMag(m);
+    // TODO: parameterize sign
+    // adjust for compass axis offsets and scale
+    for (int i=0; i < 3; i++) {
+        mag[i] = ((float) m[i] - m_offset[i]) * m_scale[i] * m_sign[i];
+    }
+    //fprintf(stdout, "m_offset=(%5.5f,%5.5f,%5.5f)\n", ahrs.c_magnetom[0],ahrs.c_magnetom[1],ahrs.c_magnetom[2]);
+  
+    return;
+}
+
+/* doing some crude gryo and accelerometer offset calibration here
+ *
+ */
+void Sensors::Calculate_Offsets()
+{
+    int samples=128;
+    
+    for (int i=0; i < 3; i++) {
+        g_offset[i] = 0;
+        a_offset[i] = 0;
+    }
+
+    for(int i=0; i < samples; i++) {  // We take some readings...
+        Read_Gyro();
+        Read_Accel();
+        for(int y=0; y < 3; y++) {   // Cumulate values
+            g_offset[y] += g[y];
+            a_offset[y] += a[y];
+        }
+        wait(0.010);
+    }
+
+    for(int y=0; y < 3; y++) {
+        g_offset[y] /= samples;
+        a_offset[y] /= samples;
+    }
+
+    //TODO: if we ever get back to using accelerometer, do something about this.
+    //a_offset[_z_] -= GRAVITY * a_sign[_z_]; // I don't get why we're doing this...?
+}
+
+
+
+void Sensors::Compass_Heading()
+{
+  /*
+  float MAG_X;
+  float MAG_Y;
+  float cos_roll;
+  float sin_roll;
+  float cos_pitch;
+  float sin_pitch;
+  
+  // See DCM.cpp Drift_correction()
+
+  // umm... doesn't the dcm already have this info in it?!
+  cos_roll = cos(ahrs.roll);
+  sin_roll = sin(ahrs.roll);
+  cos_pitch = cos(ahrs.pitch);
+  sin_pitch = sin(ahrs.pitch);
+    
+  // Tilt compensated Magnetic filed X:
+  MAG_X = mag[_x_] * cos_pitch + mag[_y_] * sin_roll * sin_pitch + mag[_z_] * cos_roll * sin_pitch;
+  // Tilt compensated Magnetic filed Y:
+  MAG_Y = mag[_y_] * cos_roll - mag[_z_] * sin_roll;
+  // Magnetic Heading
+  ahrs.MAG_Heading = atan2(-MAG_Y,MAG_X);
+  */
+}
+
+
+void Sensors::getRawMag(int rawmag[3])
+{
+    Read_Compass();
+    for (int i=0; i < 3; i++) {
+        rawmag[i] = m[i];
+    }        
+}
+
+
+// getCurrent is a macro defined above
+
+float Sensors::getVoltage() {
+    static float filter = -1.0;
+    float v = _voltage * 3.3 * 4.12712;        // 242.3mV/V
+
+    // TODO: median filter to eliminate spikes
+    if (filter < 0) {
+        filter = v * VFF;
+    } else {
+        filter += (v - filter/VFF);
+    }
+    return (filter / VFF);
+}
+
+
+
+float Sensors::getCurrent() {
+    /*static bool first=true;
+    static float history[3];
+    float tmp;
+    float sort[3];
+
+    if (first) {
+        first = false;
+        history[0] = history[1] = history[2] = _current;
+    } else {
+        sort[0] = history[0] = history[1];
+        sort[1] = history[1] = history[2];
+        sort[2] = history[2] = _current;
+    }
+    BubbleSort(sort, 3);*/
+    return (_current * 3.3 * 13.6612); // 73.20mV/A        
+}
+
+
+void Sensors::Read_Power()
+{
+    // TODO: exponential or median filtering on these to get rid of spikes
+    //
+    voltage = getVoltage();
+    current = getCurrent();
+
+    return;
+}
+
+float clampIRRanger(float x)
+{
+    float y=x;
+    
+    if (y < 0.1) 
+        y = 0.1;
+    if (y > 5.0) 
+        y = 5.0;
+    
+    return y;
+}
+
+void Sensors::Read_Camera()
+{
+    char count;
+    char data[128];
+    char addr=0x80;
+    /*
+    struct {
+        int color;
+        int x1;
+        int y1;
+        int x2;
+        int y2;
+    } blob;
+    */
+
+    /* 
+    I2C START BIT
+    WRITE: 0xA0 ACK 
+    WRITE: 0x00 ACK 
+    I2C START BIT
+    WRITE: 0xA1 ACK 
+    READ: 0x01  ACK 0x02  ACK 0x03  ACK 0x04  ACK 0x05  ACK 0x06  ACK 0x07  ACK 0x08  ACK 0x09  ACK 0x0A 
+    NACK
+    I2C STOP BIT
+    */
+
+    _cam.start();
+    _cam.write(0x11<<1);
+    _cam.write(0x01); // command to send box data
+    _cam.start();
+    _cam.write((0x11<<1 | 0x01));
+    count = _cam.read(1); // number of boxes tracked
+    if (count > 8) count = 8;
+    //fprintf(stdout, "----------\n%d\n", count);
+    int x=0;
+    for (int i=0; i < count; i++) {
+        //fprintf(stdout, "%d: ", i);
+        for (int j=0; j < 5; j++) {
+            data[x] = _cam.read(1);
+            //fprintf(stdout, "%d ", data[x]);
+            x++;
+        }
+        //fprintf(stdout, "\n");
+    }
+    _cam.read(0); // easiest to just read one more byte then NACK it
+    _cam.stop();
+}
+
+
+void Sensors::Read_Rangers()
+{
+    char data[2];
+    // Sharp GP2Y0A710YK0F
+    static float m=288.12;  // slope adc=m(dist) + b
+    static float b=219.3;
+    static float m_per_lsb=0.004883/0.38583; // 0.004883mV/lsb * 0.0098in/lsb * 1in/0.0254m = m/lsb
+    
+    _rangers.start();
+    data[0] = (0x11<<1 | 0x01); // send address + read = 1
+    _rangers.write(data[0]);       // send address
+    ranger[0] = (int) _rangers.read(1) | ((int) _rangers.read(1)) << 8;
+    ranger[1] = (int) _rangers.read(1) | ((int) _rangers.read(1)) << 8;
+    ranger[2] = (int) _rangers.read(1) | ((int) _rangers.read(0)) << 8; // don't ack the last byte
+    _rangers.stop();
+
+    /*
+    for (int q=0; q<3; q++)
+        fprintf(stdout, "%04x ", ranger[q]);    
+    fprintf(stdout, "\n");
+    */
+    
+    if (ranger[0] < 86) {
+        rightRanger = 999.0;
+    } else if (ranger[0] > 585) {
+        rightRanger = 20.0;
+    } else {
+        // Sharp GP2Y0A02YK0F
+        rightRanger = 1/(8.664e-005*ranger[0]-0.0008); // IR distance, meters
+    }
+
+    // Compute distances
+    leftRanger = clampIRRanger( m/(ranger[1]-b) );  // IR distance, meters
+    // Sonar
+    centerRanger = ranger[2] * (m_per_lsb); // Sonar distance, metersmv/in=0.0098, mv/lsb=0.0049
+}
+
+
+
+/** perform bubble sort
+ * for median filtering
+ */
+void Sensors::BubbleSort(float *num, int numLength)
+{
+    float temp;             // holding variable
+    bool flag=true;
+    
+    for(int i = 1; (i <= numLength) && flag; i++) {
+        flag = false;
+        for (int j = 0; j < (numLength -1); j++) {
+            if (num[j+1] > num[j]) {      // ascending order simply changes to <
+                temp = num[j];             // swap elements
+                num[j] = num[j+1];
+                num[j+1] = temp;
+                flag = true;
+            }
+        }
+    }
+    return;   //arrays are passed to functions by address; nothing is returned
+}
diff -r 000000000000 -r 826c6171fc1b Sensors/Sensors.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Sensors/Sensors.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,132 @@
+/*
+
+MinIMU-9-Arduino-AHRS
+Pololu MinIMU-9 + Arduino AHRS (Attitude and Heading Reference System)
+
+Copyright (c) 2011 Pololu Corporation.
+http://www.pololu.com/
+
+MinIMU-9-Arduino-AHRS is based on sf9domahrs by Doug Weibel and Jose Julio:
+http://code.google.com/p/sf9domahrs/
+
+sf9domahrs is based on ArduIMU v1.5 by Jordi Munoz and William Premerlani, Jose
+Julio and Doug Weibel:
+http://code.google.com/p/ardu-imu/
+
+MinIMU-9-Arduino-AHRS is free software: you can redistribute it and/or modify it
+under the terms of the GNU Lesser General Public License as published by the
+Free Software Foundation, either version 3 of the License, or (at your option)
+any later version.
+
+MinIMU-9-Arduino-AHRS is distributed in the hope that it will be useful, but
+WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for
+more details.
+
+You should have received a copy of the GNU Lesser General Public License along
+with MinIMU-9-Arduino-AHRS. If not, see <http://www.gnu.org/licenses/>.
+
+*/
+#ifndef __SENSORS_H
+#define __SENSORS_H
+
+/** Sensor interface library abstracts sensor drivers, next step to a pluggable architecture */
+
+#include "L3G4200D.h"
+#include "LSM303DLM.h"
+//#include "HMC5843.h"
+#include "IncrementalEncoder.h"
+#include "Matrix.h"
+
+// Sensor axes
+#define _x_ 0
+#define _y_ 1
+#define _z_ 2
+
+// Magnetometer calibration constants
+//#define M_OFFSET_X -20.4416 // calibrated 02/13/2012 mes
+//#define M_OFFSET_Y -67.2318
+//#define M_OFFSET_Z 6.0950
+//#define M_OFFSET_X 12.8922 // calibrated 12/31/2012 mes
+//#define M_OFFSET_Y -7.3453
+//#define M_OFFSET_Z -147.8652
+//#define M_SCALE_X 570.06
+//#define M_SCALE_Y 532.83
+//#define M_SCALE_Z 480.95
+
+//#define M_X_MIN -654 // calibrated 12/8/2011 mes
+//#define M_X_MAX 457
+//#define M_Y_MIN -744 
+//#define M_Y_MAX 369
+//#define M_Z_MIN -573
+//#define M_Z_MAX 464
+
+// Chassis specific parameters
+#define WHEEL_STRIPES 32
+#define WHEEL_CIRC    0.321537 // m; calibrated with 4 12.236m runs. Wheel circumference measured 13.125" or 0.333375m
+#define WHEELBASE     0.290
+#define TRACK         0.280
+
+class Sensors {
+public:
+    Sensors(void);
+    void Compass_Calibrate(float offset[3], float scale[3]);
+    void Read_Encoders(void);
+    void Read_Gyro(void);
+    void Read_Accel(void);
+    void Read_Compass(void);
+    void Calculate_Offsets(void);
+    void Compass_Heading(void);
+    void getRawMag(int mag[3]);
+    float getVoltage(void);
+    float getCurrent(void);
+    void Read_Power(void);
+    void Read_Rangers();
+    void Read_Camera();
+    int g[3];                               // raw gyro value
+    int gTemp;                              // raw gyro temperature
+    int a[3];                               // raw accelerometer value
+    int m[3];                               // raw magnetometer value
+    int g_offset[3];                        // raw gyro offset
+    int a_offset[3];                        // raw accel offset
+    float m_offset[3];                      // magnetometer offset
+    float g_scale[3];                       // gyro scaling factor
+    float m_scale[3];                       // magnetometer scale
+    int g_sign[3];                          // correct sensor signs
+    int a_sign[3];
+    int m_sign[3]; 
+    float gyro[3];                          // corrected gyro value
+    float accel[3];                         // corrected accelerometer value
+    float mag[3];                           // corrected magnetometer value
+    int ranger[3];                          // ranger values
+    float leftRanger;
+    float rightRanger;
+    float centerRanger;
+    float voltage;                          // battery voltage in volts
+    float current;                          // system current draw in amps
+    unsigned int leftTotal;                 // total number of ticks
+    unsigned int rightTotal;                // total number of ticks
+    unsigned int leftCount;                 // left rear encoder count
+    unsigned int rightCount;                // right rear encoder count
+    float lrEncDistance;                    // left rear encoder distance
+    float rrEncDistance;                    // right rear encoder distance
+    float lrEncSpeed;                       // left rear encoder speed
+    float rrEncSpeed;                       // right rear encoder speed
+    float encDistance;                      // encoder distance since last check
+    float encSpeed;                         // encoder calculated speed
+
+    AnalogIn _voltage;                      // Voltage from sensor board
+    AnalogIn _current;                      // Current from sensor board
+    IncrementalEncoder _left;               // Left wheel encoder
+    IncrementalEncoder _right;              // Right wheel encoder
+    L3G4200D _gyro;                         // MinIMU-9 gyro
+    LSM303DLM _compass;                     // MinIMU-9 compass/accelerometer
+    I2C _rangers;                           // Arduino ranger board
+    I2C _cam;                               // Propeller camer aboard
+    //HMC5843 compass;
+
+private:
+    void BubbleSort(float *num, int numLength);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b SimpleFilter.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SimpleFilter.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/shimniok/code/SimpleFilter/#70348515ed2f
diff -r 000000000000 -r 826c6171fc1b SystemState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/SystemState.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,86 @@
+#ifndef _SYSTEMSTATE_H
+#define _SYSTEMSTATE_H
+
+#define SSBUF 0x2F
+
+/** System State is the main mechanism for communicating current realtime system state to
+ * the rest of the system for logging, data display, etc.
+ */
+
+/* struct systemState
+ * structure containing system sensor data
+ ****** System Status
+ * millis               number of milliseconds since epoch (or startup)
+ * current              current draw in amps
+ * voltage              voltage in volts
+ ****** Data reported by IMU
+ * g[3]                 raw 3-axis gyro values; if using 1-axis, then store data in gx
+ * gTemp                Gyro temperature
+ * a[3]                 raw 3-axis accelerometer values
+ * m[3]                 raw 3-axis magnetometer values; if using 2d then store data in mx and my
+ * gHeading             independently calculated gyro heading in degrees
+ * cHeading             independently calculated compass heading in degrees
+ ****** AHRS Estimates
+ * roll, pitch, yaw     estimated attitude in degrees relative to the world frame
+ ****** Data reported by GPS
+ * gpsLatitude          raw GPS latitude in fractional degrees (e.g., 39.123456)
+ * gpsLongitude         raw GPS longitude in fractional degrees (e.g., -104.123456
+ * gpsCourse            raw GPS course in degrees
+ * gpsSpeed             raw GPS speed in mph
+ * gpsHDOP              raw GPS Horizontal Dilution of Precision
+ ****** Odometry data
+ * lrEncDistance        left rear encoder distance since last log update
+ * rrEncDistance        right rear encoder distance since last log update
+ * lrEncSpeed           left rear encoder speed 
+ * rrEncSpeed           right rear encoder speed
+ * encHeading           estimated heading based on encoder readings
+ ****** Estimated Position and Heading
+ * estHeading           estimated heading in degrees, this is the robot's reference for heading
+ * estLatitude          estimated latitude in fractional degrees (e.g., 39.123456)
+ * estLongitude         estimated longitude in fractional degrees (e.g., -104.123456)
+ * estNorthing          some algorithms use UTM.  Estimated UTM northing
+ * estEasting           estimated UTM easting
+ * estX, estY           some algorithms use simple x, y distance from origin (meters)
+ ****** Waypoint data
+ * nextWaypoint         integer ID of the next waypoint
+ * bearing              estimated bearing to next waypoint in degrees
+ * distance             estimated distance to next waypoint in meters
+ ****** Control data
+ * throttle             raw servo setting(units?)
+ * steering             raw servo setting(units?)
+ */
+typedef struct {
+    unsigned int millis;
+    float current, voltage;
+    int g[3];
+    int gTemp;
+    int a[3];
+    int m[3];
+    float gHeading;
+    float cHeading;
+    //float roll, pitch, yaw;
+    double gpsLatitude;
+    double gpsLongitude;
+    float gpsCourse;
+    float gpsSpeed;
+    float gpsHDOP;
+    int gpsSats;
+    float lrEncDistance, rrEncDistance;
+    float lrEncSpeed, rrEncSpeed;
+    float encHeading;
+    float estHeading;
+    double estLatitude, estLongitude;
+    //double estNorthing, estEasting;
+    float estX, estY;
+    unsigned short nextWaypoint;
+    float bearing;
+    float distance;
+    float gbias;
+    float errAngle;
+    float leftRanger;
+    float rightRanger;
+    float centerRanger;
+    float crossTrackErr;
+} SystemState;
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/Beep/Beep.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Beep/Beep.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,33 @@
+#include "mbed.h"
+#include "Beep.h"
+
+/** Create a Beep object connected to the specified PwmOut pin
+ *
+ * @param pin PwmOut pin to connect to 
+ */
+Beep::Beep(PinName pin) : _pwm(pin) {
+    _pwm.write(0.0);     // after creating it have to be off
+}
+
+ /** Stop the beep instantaneously.
+  */
+void Beep::nobeep() {
+    _pwm.write(0.0);
+}
+
+/** Beep with given frequency and duration.
+ *
+ * @param frequency - the frequency of the tone in Hz
+ * @param time - the duration of the tone in seconds
+ */
+     
+void Beep::beep(float freq, float time) {
+
+    _pwm.period(1.0/freq);
+    _pwm.write(0.5);            // 50% duty cycle - beep on
+    toff.attach(this,&Beep::nobeep, time);   // time to off
+}
+
+
+
+
diff -r 000000000000 -r 826c6171fc1b UI/Beep/Beep.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Beep/Beep.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,49 @@
+#ifndef MBED_BEEP_H
+#define MBED_BEEP_H
+
+#include "mbed.h"
+
+/** Generates a tone with a buzzer, based on a PwmOut
+ * The class use a timeout to switch off the sound  - it is not blocking while making noise
+ *
+ * Example:
+ * @code
+ * // Beep at 2kHz for 0.5 seconds
+ * #include "mbed.h"
+ * #include "Beep.h"
+ * 
+ * Beep buzzer(p21);
+ * 
+ * int main() {
+ *        ...
+ *   buzzer.beep(2000,0.5);    
+ *       ...
+ * }
+ * @endcode
+ */
+class Beep {
+
+public:
+
+/** Create a Beep object connected to the specified PwmOut pin
+ *
+ * @param pin PwmOut pin to connect to 
+ */
+    Beep(PinName pin);
+
+/** Beep with given frequency and duration.
+ *
+ * @param frequency - the frequency of the tone in Hz
+ * @param time - the duration of the tone in seconds
+ */
+    void beep(float frequency, float time);
+
+/** stop the beep instantaneously. Not typically needed, but here just in case
+ */
+    void nobeep();
+
+private :
+    PwmOut _pwm;
+    Timeout toff;
+};
+#endif
diff -r 000000000000 -r 826c6171fc1b UI/Buttons/Buttons.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Buttons/Buttons.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,51 @@
+#include "Buttons.h"
+#include "PinDetect.h"
+
+PinDetect nextButton(p14);
+PinDetect selectButton(p16);            // Input selectButton
+PinDetect prevButton(p15);
+
+Buttons::Buttons(void): which(0), pressed(false)
+{
+}
+
+void Buttons::init()
+{
+
+    // Set up button (plugs into two GPIOs, active low
+    selectButton.mode(PullUp);
+    selectButton.setSamplesTillAssert(50);
+    selectButton.setAssertValue(0); // active low logic
+    selectButton.setSampleFrequency(50); // us
+    selectButton.attach_asserted( this, &Buttons::selectPressed );
+    
+    nextButton.mode(PullUp);
+    nextButton.setSamplesTillAssert(50);
+    nextButton.setAssertValue(0); // active low logic
+    nextButton.setSampleFrequency(50); // us
+    nextButton.attach_asserted( this, &Buttons::nextPressed );
+
+    prevButton.mode(PullUp);
+    prevButton.setSamplesTillAssert(50);
+    prevButton.setAssertValue(0); // active low logic
+    prevButton.setSampleFrequency(50); // us
+    prevButton.attach_asserted( this, &Buttons::prevPressed );
+}
+
+void Buttons::nextPressed() 
+{
+    pressed = true;
+    which = NEXT_BUTTON;
+}
+
+void Buttons::prevPressed() 
+{
+    pressed = true;
+    which = PREV_BUTTON;
+}
+
+void Buttons::selectPressed()
+{
+    pressed = true;
+    which = SELECT_BUTTON;
+}
diff -r 000000000000 -r 826c6171fc1b UI/Buttons/Buttons.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Buttons/Buttons.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,20 @@
+#ifndef __BUTTONS_H
+#define __BUTTONS_H
+
+#define NEXT_BUTTON   1
+#define PREV_BUTTON   2
+#define SELECT_BUTTON 3
+
+class Buttons {
+public:
+    Buttons();
+    void init(void);
+    void nextPressed(void);
+    void prevPressed(void);
+    void selectPressed(void);
+    
+    int which;
+    bool pressed;
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/Buttons/DebounceIn.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Buttons/DebounceIn.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/AjK/code/DebounceIn/#91a2e988ba9d
diff -r 000000000000 -r 826c6171fc1b UI/Buttons/PinDetect.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Buttons/PinDetect.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/AjK/code/PinDetect/#cb3afc45028b
diff -r 000000000000 -r 826c6171fc1b UI/LCD/Bargraph.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/Bargraph.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,63 @@
+#include "Bargraph.h"
+
+#define WIDTH 8
+#define HEIGHT 9
+
+SerialGraphicLCD *Bargraph::lcd = 0;
+
+Bargraph::Bargraph(int x, int y, int size, char name):
+    _x(x), _y(y), _x2(x+WIDTH), _y2(y+size-1), _s(size), _n(name), _last(0)
+{
+}
+
+Bargraph::Bargraph(int x, int y, int size, int width, char name):
+    _x(x), _y(y), _x2(x+width-1), _y2(y+size-1), _s(size), _w(width), _n(name), _last(0)
+{
+}
+
+void Bargraph::init() 
+{
+    if (lcd) {
+        if (_n != ' ') {
+            lcd->posXY(_x, _y2+2); // horizontal center
+            lcd->printf("%c", _n);
+        }
+        lcd->rect(_x, _y, _x2, _y2, true);
+        int value = _last;
+        _last = 0;
+        update(value);
+    }
+}
+
+void Bargraph::calibrate(float min, float max)
+{
+    _min = min;
+    _max = max;
+}
+
+void Bargraph::update(float value)
+{
+    int ivalue;
+
+    ivalue = (int) ((value - _min) * (_s-1)/(_max - _min));
+
+    update(ivalue);
+
+    return;
+}
+
+void Bargraph::update(int value)
+{
+    if (lcd) {
+        if (value >= 0 && value < _s) {
+            int newY = _y2-value;
+            
+            for (int y=_y+1; y < _y2; y++) {
+                lcd->line(_x+1, y, _x2-1, y, (y > newY));
+                wait_ms(5);
+            }
+        }
+        _last = value;
+    }
+}
+
diff -r 000000000000 -r 826c6171fc1b UI/LCD/Bargraph.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/Bargraph.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,30 @@
+#ifndef __BARGRAPH_H
+#define __BARGRAPH_H
+
+#include "SerialGraphicLCD.h"
+
+class Bargraph {
+public:
+    Bargraph(int x, int y, int size, char name);
+    Bargraph(int x, int y, int size, int width, char name);
+    void init(void);
+    void calibrate(float min, float max);
+    void update(float value);
+    void update(int value);
+
+    static SerialGraphicLCD *lcd;
+
+private:
+    int _x;
+    int _y;
+    int _x2;
+    int _y2;
+    int _s;
+    int _w;
+    float _min;
+    float _max;
+    char _n;
+    int _last;
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/LCD/GPSStatus.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/GPSStatus.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,51 @@
+#include "GPSStatus.h"
+
+#define WIDTH 8
+#define HEIGHT 9
+
+SerialGraphicLCD *GPSStatus::lcd = 0;
+
+GPSStatus::GPSStatus(int x, int y):
+    _x(x), _y(y)
+{
+}
+
+void GPSStatus::init() 
+{
+    if (lcd) {
+        lcd->pixel(_x+1, _y+1, true);
+        lcd->pixel(_x+2, _y+1, true);
+        lcd->pixel(_x+3, _y+1, true);
+        lcd->pixel(_x+2, _y+2, true);
+        lcd->pixel(_x+2, _y+3, true);
+        lcd->pixel(_x+3, _y+3, true);
+        lcd->pixel(_x+4, _y+3, true);
+        lcd->pixel(_x+2, _y+4, true);
+        lcd->pixel(_x+5, _y+4, true);
+        lcd->pixel(_x+1, _y+5, true);
+        lcd->pixel(_x+3, _y+5, true);
+        lcd->pixel(_x+1, _y+6, true);
+        lcd->pixel(_x+2, _y+7, true);
+        lcd->posXY(_x+10, _y);
+        _last = 0;
+    }
+}
+
+void GPSStatus::update(float hdop)
+{
+    lcd->pixel(_x+5, _y+1, hdop < 3.0);    
+
+    lcd->pixel(_x+6, _y+1, hdop < 2.0);    
+    lcd->pixel(_x+6, _y+2, hdop < 2.0);    
+
+    lcd->pixel(_x+7, _y+1, hdop < 1.5);    
+    lcd->pixel(_x+7, _y+2, hdop < 1.5);    
+    lcd->pixel(_x+7, _y+3, hdop < 1.5);    
+
+    lcd->pixel(_x+8, _y+1, hdop < 1.1);    
+    lcd->pixel(_x+8, _y+2, hdop < 1.1);    
+    lcd->pixel(_x+8, _y+3, hdop < 1.1);    
+    lcd->pixel(_x+8, _y+4, hdop < 1.1);    
+ 
+    return;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/LCD/GPSStatus.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/GPSStatus.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,24 @@
+#ifndef __GPSSTATUS_H
+#define __GPSSTATUS_H
+
+#include "SerialGraphicLCD.h"
+
+class GPSStatus {
+public:
+    GPSStatus(int x, int y);
+    void init();
+    void update(float hdop);
+
+    static SerialGraphicLCD *lcd;
+
+private:
+    int _x;
+    int _y;
+    int _s;
+    float _min;
+    float _max;
+    char _n;
+    int _last;
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/LCD/lcd.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/lcd.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,38 @@
+#include "mbed.h"
+/*
+void lcdInit()
+{
+    lcd.baud(4800);
+    lcd.printf("4800");
+    lcd.printf("%c%c", 0x7C, 13);
+    lcd.baud(9600);
+    lcd.printf("9600");
+}
+
+void lcdClear()
+{
+    lcd.printf("%c%c",0xFE,0x01); // command, clear
+    wait(0.020);
+}    
+
+void lcdSetPos(int x, int y)
+{
+    uint8_t pos=0;
+
+    if ( x >= 0 && x < 16 && y >= 0 && y < 2)
+        pos = x + y*64;
+        
+    pos |= (1<<7);
+    
+    lcd.printf("%c%c",0xFE,pos);
+}
+
+void lcdSetSplash(const char *s1, const char *s2)
+{
+    lcdClear();
+    lcd.printf(s1);
+    lcdSetPos(0,1);
+    lcd.printf(s2);
+    lcd.printf("%c%c",0x7C,0x0A);
+}
+*/
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/LCD/lcd.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/LCD/lcd.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,11 @@
+#ifndef __LCD_H
+#define __LCD_H
+
+void lcdSetSplash(const char *s1, const char *s2);
+void lcdInit(void);
+void lcdClear(void);
+void lcdSetPos(int x, int y);
+
+extern Serial lcd;
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/Menu/Menu.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Menu/Menu.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,62 @@
+#include "mbed.h"
+#include "Menu.h"
+#include <string.h>
+
+Menu::Menu():
+    _item(0), _itemCount(0)
+{
+}
+
+void Menu::add(char *name, FunctionPtr f)
+{
+    if (_itemCount < _ITEM_MAX) {
+        _exec[_itemCount] = f;
+        strncpy(_name[_itemCount], name, NAMESIZ-1);
+        _itemCount++;
+    }
+    
+    return;
+}
+
+void Menu::next()
+{
+    _item++;
+    if (_item >= _itemCount) _item = 0;
+    
+    return;
+}
+
+void Menu::prev()
+{
+    if (_item == 0) _item = _itemCount;
+    _item--;
+    
+   return;
+}
+
+void Menu::select()
+{
+    (_exec[_item])();
+}
+
+char *Menu::getItemName(int i)
+{
+    return _name[i];
+}
+
+
+char *Menu::getItemName()
+{
+    return _name[_item];
+}
+
+void Menu::printAll()
+{
+    fprintf(stdout, "Menus:\n");
+    for (int i=0; i < _itemCount; i++) {
+        fprintf(stdout, "%s\n", _name[i]);
+    }
+    fprintf(stdout, "\n");
+    
+    return;   
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/Menu/Menu.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/Menu/Menu.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,49 @@
+#define _ITEM_MAX 10
+#define NAMESIZ 20
+
+typedef int (*FunctionPtr)();
+
+/** Simple menu interface model
+ */
+class Menu {
+public:
+
+    /** Create a new menu model
+     */
+    Menu();
+    
+    /** add a new menu item
+     */
+    void add(char *name, FunctionPtr f);
+    
+    /** select the next menu item as the current item
+     */
+    void next(void);
+    
+    /** select the previous menu item as the current item
+     */
+    void prev(void);
+    
+    /** run the function associated with the current item
+     */
+    void select(void);
+    
+    /** return the text for the current item
+     */
+    char *getItemName(void);
+
+    /** return text for a specified item
+     */
+    char *getItemName(int i);
+    
+    /** print all the menu items
+     */
+    void printAll(void);
+    
+private:
+    short _item;
+    short _itemCount;
+    char _name[_ITEM_MAX][NAMESIZ];
+    FunctionPtr _exec[_ITEM_MAX];
+};
+
diff -r 000000000000 -r 826c6171fc1b UI/SerialGraphicLCD/SerialGraphicLCD.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/SerialGraphicLCD/SerialGraphicLCD.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,157 @@
+#include "SerialGraphicLCD.h"
+
+#define XSIZE 6
+#define YSIZE 9
+
+SerialGraphicLCD::SerialGraphicLCD(PinName tx, PinName rx): 
+    Serial(tx, rx), _firmware(SFE_FW)
+{
+    baud(115200);               // default baud rate
+    resolution(LCD_128x64);     // default resolution
+}
+
+SerialGraphicLCD::SerialGraphicLCD(PinName tx, PinName rx, int firmware):
+    Serial(tx, rx), _firmware(firmware)
+{
+    baud(115200);               // default baud rate
+    resolution(LCD_128x64);     // default resolution
+}
+
+void SerialGraphicLCD::clear() {
+    putc(0x7c);
+    putc(0x00);
+}
+
+void SerialGraphicLCD::pos(int col, int row) {
+    if (_firmware == SD_FW)
+        posXY(XSIZE*col, (YSIZE*row));
+    else if (_firmware == SFE_FW)
+        posXY(XSIZE*col, _yMax-(YSIZE*row)-1);
+}
+
+void SerialGraphicLCD::posXY(int x, int y) {
+    putc(0x7c);
+    putc(0x18);
+    putc(x);
+    putc(0x7c);
+    putc(0x19);
+    putc(y);
+}
+
+void SerialGraphicLCD::pixel(int x, int y, bool set) {
+    putc(0x7c);
+    putc(0x10);
+    putc(x);
+    putc(y);
+    putc((set) ? 0x01 : 0x00);
+}
+
+void SerialGraphicLCD::line(int x1, int y1, int x2, int y2, bool set) {
+    putc(0x7c);
+    putc(0x0c);
+    putc(x1);
+    putc(y1);
+    putc(x2);
+    putc(y2);
+    putc((set) ? 0x01 : 0x00);
+}
+
+void SerialGraphicLCD::circle(int x, int y, int r, bool set) {
+    putc(0x7c);
+    putc(0x03);
+    putc(x);
+    putc(y);
+    putc(r);
+    putc((set) ? 0x01 : 0x00);
+}
+
+// Unfortunately, the datasheet for the stock firmware is incorrect;
+// the box command does not take a 5th parameter for draw/erase like the others
+// However, it does in the sd firmware
+void SerialGraphicLCD::rect(int x1, int y1, int x2, int y2) {
+    putc(0x7c);
+    putc(0x0f);
+    putc(x1);
+    putc(y1);
+    putc(x2);
+    putc(y2);
+    if (_firmware == SD_FW)
+        putc(0x01);
+}
+
+void SerialGraphicLCD::rect(int x1, int y1, int x2, int y2, bool set) {
+    putc(0x7c);
+    putc(0x0f);
+    putc(x1);
+    putc(y1);
+    putc(x2);
+    putc(y2);
+    if (_firmware == SD_FW)
+        putc((set) ? 0x01 : 0x00);
+}
+
+void SerialGraphicLCD::rectFill(int x1, int y1, int x2, int y2, char fillByte) {
+    if (_firmware == SD_FW) {
+
+        // Bugs in firmware; if y2-y1 == 2, nothing drawn; if y2-y1 == 3, fill is 4 tall
+//        if ((y2 - y1) > 3) {
+            putc(0x7c);
+            putc(0x12);
+            putc(x1);
+            putc(y1);
+            putc(x2+1); // bug in firmware, off-by-one on x2
+            putc(y2);
+            putc(fillByte);
+//        } else {
+//            for (int y=y1; y <= y2; y++)
+//                line(x1, y, x2, y, fillByte == FILL);
+//        }            
+    }
+}
+
+void SerialGraphicLCD::erase(int x1, int y1, int x2, int y2) {
+    putc(0x7c);
+    putc(0x05);
+    putc(x1);
+    putc(y1);
+    putc(x2);
+    putc(y2);
+}
+
+void SerialGraphicLCD::backlight(int i) {
+    if (i >= 0 && i <= 100) {
+        putc(0x7c);
+        putc(0x02);
+        putc(i);
+    }
+}
+
+void SerialGraphicLCD::reverseMode() {
+    putc(0x7c);
+    putc(0x12);
+}
+
+void SerialGraphicLCD::resolution(int type) {
+    switch (type) {
+    case LCD_128x64 :
+        resolution(128, 64);
+        break;
+    case LCD_160x128 :
+        resolution(160, 128);
+        break;
+    }
+}
+
+void SerialGraphicLCD::resolution(int x, int y) {
+    _xMax = x;
+    _yMax = y;
+}
+
+
+void SerialGraphicLCD::lcdbaud(int b) {
+    if (b > 0 && b < 7) {
+        putc(0x7c);
+        putc(0x07);
+        putc(b+'0');
+    }
+}    
diff -r 000000000000 -r 826c6171fc1b UI/SerialGraphicLCD/SerialGraphicLCD.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/SerialGraphicLCD/SerialGraphicLCD.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,206 @@
+/* Serial Graphics LCD Driver for Sparkfun Serial Graphics LCD, LCD-09351; and Graphic 
+ * LCD Serial Backpack, LCD-09352.
+ *
+ * @author Michael Shimniok http://www.bot-thoughts.com/
+ *
+ */
+#ifndef _SERIALGRAPHICLCD_H
+#define _SERIALGRAPHICLCD_H
+
+#include "mbed.h"
+
+/** Firmware modes */
+#define SFE_FW 0        // Stock SFE firmware
+#define SD_FW  1        // summoningdark firmware http://sourceforge.net/projects/serialglcd/
+
+/** Modes for SD firmware */
+#define FILL 0xFF
+#define CLEAR 0x00
+
+/** LCD Baud Rates */
+#define LCD_4800   1
+#define LCD_9600   2
+#define LCD_19200  3
+#define LCD_38400  4
+#define LCD_57600  5
+#define LCD_115200 6
+
+/** LCD Types */
+#define LCD_128x64  1
+#define LCD_160x128 2
+
+/** Interface to the Sparkfun Serial Graphic LCD, LCD-09351; and Graphic 
+ * LCD Serial Backpack, LCD-09352. Derived class from Serial so that you
+ * can conveniently printf(), putc(), etc to the display.
+ * 
+ * Example:
+ * @code
+ * #include "mbed.h"
+ * #include "SerialGraphicLCD.h"
+ * 
+ * SerialGraphicLCD lcd(p26, p25);
+ * 
+ * int main() {
+ *   lcd.baud(115200); // default baud rate
+ *   while (1) {
+ *      lcd.clear();
+ *      lcd.rect(3, 3, 20, 20);
+ *      lcd.printf("Hello World!");
+ *      lcd.pixel(14, 35, true);
+ *      lcd.pixel(16, 36, true);
+ *      lcd.pixel(18, 37, true);
+ *      lcd.pos(5, 30);
+ *      lcd.printf("Hi");
+ *      lcd.circle(50, 20, 20, true);
+ *      lcd.pos(50, 20);
+ *      lcd.printf("Howdy");
+ *      lcd.line(0, 0, 25, 25, true);
+ *      wait(2);
+ *   }
+ * }
+ * @endcode
+ */
+class SerialGraphicLCD: public Serial {
+public:
+    /** Create a new interface to a Serial Graphic LCD
+     * Note that the display lower left corner is coordinates 0, 0.
+     * Rows start at the top at 0, columns start at the left at 0.
+     * @param tx -- mbed transmit pin
+     * @param rx -- mbed receive pin
+     */
+    SerialGraphicLCD(PinName tx, PinName rx);
+    
+    /** Create a new interface to a Serial Graphic LCD
+     * Note that the display lower left corner is coordinates 0, 0.
+     * Rows start at the top at 0, columns start at the left at 0.
+     * @param tx -- mbed transmit pin
+     * @param rx -- mbed receive pin
+     * @param firmware -- SFE_FW, stock firmware or SD_FW, summoningdark firmware
+     */
+    SerialGraphicLCD(PinName tx, PinName rx, int firmware);
+
+    /** clear the screen
+     */
+    void clear(void);
+
+    /** set text position in rows, columns
+     *
+     * @param col is the col coordinate
+     * @param row is the row coordinate
+     */
+    void pos(int col, int row);
+    
+    /** set text position in x, y coordinates
+     *
+     * @param x is the x coordinate
+     * @param y is the y coordinate
+     */
+    void posXY(int x, int y);
+    
+    /** set or erase a pixel
+     *
+     * @param x is the x coordinate
+     * @param y is the y coordinate
+     * @param set if true sets the pixel, if false, erases it
+     */
+    void pixel(int x, int y, bool set);
+    
+    /** draw or erase a line
+     *
+     * @param x1 is the x coordinate of the start of the line
+     * @param y1 is the y coordinate of the start of the line
+     * @param x2 is the x coordinate of the end of the line
+     * @param y2 is the y coordinate of the end of the line
+     * @param set if true sets the line, if false, erases it
+     */
+    void line(int x1, int y1, int x2, int y2, bool set);
+    
+    /** set or reset a circle
+     *
+     * @param x is the x coordinate of the circle center
+     * @param y is the y coordinate of the circle center
+     * @param r is the radius of the circle
+     * @param set if true sets the pixel, if false, clears it
+     */
+    void circle(int x, int y, int r, bool set);
+    
+    /** draw a rectangle
+     *
+     * @param x1 is the x coordinate of the upper left of the rectangle
+     * @param y1 is the y coordinate of the upper left of the rectangle
+     * @param x2 is the x coordinate of the lower right of the rectangle
+     * @param y2 is the y coordinate of the lower right of the rectangle
+     */
+    void rect(int x1, int y1, int x2, int y2);
+
+    /** draw or erase a rectangle (SD firmware only)
+     *
+     * @param x1 is the x coordinate of the upper left of the rectangle
+     * @param y1 is the y coordinate of the upper left of the rectangle
+     * @param x2 is the x coordinate of the lower right of the rectangle
+     * @param y2 is the y coordinate of the lower right of the rectangle
+     */
+    void rect(int x1, int y1, int x2, int y2, bool set);    
+
+    /** Draw a filled box. 
+     *
+     * @param x1 is the x coordinate of the upper left of the rectangle
+     * @param y1 is the y coordinate of the upper left of the rectangle
+     * @param x2 is the x coordinate of the lower right of the rectangle
+     * @param y2 is the y coordinate of the lower right of the rectangle
+     * @param fillByte describes 1 8-pixel high stripe that is repeated every x 
+     * pixels and every 8 y pixels. The most useful are CLEAR (0x00) to clear the box, and FILL (0xFF) to fill it.
+	 */
+    void rectFill(int x1, int y1, int x2, int y2, char fillByte);
+    
+    /** erase a rectangular area
+     *
+     * @param x1 is the x coordinate of the upper left of the area
+     * @param y1 is the y coordinate of the upper left of the area
+     * @param x2 is the x coordinate of the lower right of the area
+     * @param y2 is the y coordinate of the lower right of the area
+     */
+    void erase(int x1, int y1, int x2, int y2);
+    
+    /** set backlight duty cycle
+     *
+     * @param i is the duty cycle from 0 to 100; 0 is off, 100 is full power
+     */
+    void backlight(int i);
+    
+    /** clear screen and put in reverse mode
+     */
+    void reverseMode(void);
+
+    /** configure the lcd baud rate so you have to call this along with baud() to change
+     * communication speeds
+     *
+     * @param b is the baud rate, LCD_4800, LCD_9600, LCD_19200, LCD_38400, LCD_57600 or LCD_115200
+     */
+    void lcdbaud(int b);
+    
+    
+    /** sets the resolution of the LCD so that the pos() call works properly
+     * defaults to LCD_128x64.
+     *
+     * @param type is the type of LCD, either LCD_128x64 or LCD_160x128
+     */
+    void resolution(int type);
+
+    /** sets the resolution of the LCD in x and y coordinates which determines
+     * how rows and columns are calculated in the pos() call.  Defaults to
+     * x=128, y=64
+     *
+     * @param x is the number of horizontal pixels
+     * @param y is the number of vertical pixels
+     */
+    void resolution(int x, int y);
+    
+    private:
+        int _xMax;
+        int _yMax;
+        int _firmware;
+};
+
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b UI/shell.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/shell.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,333 @@
+#include <stdio.h>
+#include "mbed.h"
+#include "stdint.h"
+#include "DirHandle.h"
+#include "SDHCFileSystem.h"
+#include "util.h"
+#include "Buttons.h"
+
+extern SDFileSystem sd;
+extern Serial pc;
+extern Buttons keypad;
+
+char cwd[64];
+char buf[128];
+bool debug=false;
+
+void shell(void);
+void termInput(char *cmd);
+void resolveDirectory(char *newpath, char *path);
+void splitName(char *path, char *dirname, char *basename);
+void ls(char *path);
+void cd(char *path);
+void pwd(void);
+void touch(char *path);
+void head(char *path);
+void cat(char *path);
+void send(char *path);
+
+void shell() {
+    FILE *fp;
+    char newpath[64], *arg, cmd[64], cmdline[64];
+    bool done=false;
+
+    //Logger.SelectCRCMode(1);
+    
+    //pc.printf("Formatting...\n");
+    //int i = Logger.format(32);
+    //pc.printf("format result: %d\n", i);
+
+    if ((fp = fopen("/log/message.txt", "w")) != NULL) {
+        for (int i=0; i < 20; i++)
+            fprintf(fp, "Hello, World!\n");
+        fclose(fp);
+        //pc.printf("created!\n");
+    } else {
+        pc.printf("Error creating file\n");
+    }
+    pc.printf("\n");
+    
+    strcpy(cwd, "/log");
+
+    while (!done) {
+        termInput(cmdline);
+        arg = split(cmd, cmdline, 64, ' ');
+        resolveDirectory(newpath, arg);
+        
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            break;
+        }        
+        
+        if (debug) pc.printf("cmdline:<%s> cmd:<%s> arg:<%s> newpath:<%s>\n", cmdline, cmd, arg, newpath);
+        
+        if (!strcmp(cmd, "ls")) {
+            ls(newpath);
+        } else if (!strcmp(cmd, "cd")) {
+            cd(newpath);
+        } else if (!strcmp(cmd, "pwd")) {
+            pwd();
+        } else if (!strcmp(cmd, "head")) {
+            head(newpath);
+        } else if (!strcmp(cmd, "cat")) {
+            cat(newpath);
+        } else if (!strcmp(cmd, "send")) {
+            send(newpath);
+        } else if (!strcmp(cmd, "mkdir")) {
+            mkdir(newpath, 1023);
+        } else if (!strcmp(cmd, "debug")) {
+            debug = !debug;
+        } else if (!strcmp(cmd, "touch")) {
+            touch(newpath);
+        } else if (!strcmp(cmd, "rm")) {
+            remove(newpath);
+        } else if (!strcmp(cmd, "exit")) {
+            done = true;
+        } else if (cmd[0] == '\0') {
+            // ignore
+        } else {
+            pc.printf("%s: command not found\n", cmd);
+        }
+    }
+
+/*
+    pc.printf("Printing splitName()\n");
+    splitName("/SDCard/testdir", dirname, basename);
+    pc.printf("%s %s\n", dirname, basename);
+
+    pc.printf("Printing resolveDirectory()\n");
+    resolveDirectory(newpath, "test");
+    pc.printf("%s\n", newpath);
+*/
+
+//    remove("/SDCard/testdir/TEST.txt");
+    
+    /*
+    int test = rename("/SDCard/message.txt", "/SDCard/message2.txt");
+    fp = fopen("/SDCard/message.txt", "a");
+    fprintf(fp, "  Result = %d", test);
+    fclose(fp);
+    */
+
+    pc.printf ("exiting shell\n");
+
+    return;
+}
+
+
+/** termInput
+ *
+ */
+void termInput(char *cmd) {
+    int i=0;
+    char c;
+    bool done = false;
+    
+    memset(cmd, 0, 64);
+    
+    pc.printf("# ", cwd);
+    do {
+        cmd[i] = 0;
+        c = pc.getc();
+        if (c == '\r') { // if return is hit, we're done, don't add \r to cmd
+            done = true;
+        } else if (i < 64-1) {
+            if (c == 0x7f || c == '\b') { // backspace or delete
+                if (i > 0) { // if we're at the beginning, do nothing
+                    i--;
+                    pc.printf("\b \b");
+                }
+            } else {
+                pc.printf("%c", c);
+                cmd[i++] = c;
+            }
+        }
+    } while (!done);
+    pc.printf("\n");
+} 
+
+/** resolveDirectory
+ * resolve the directory path provided, given the cwd
+ */
+void resolveDirectory(char *newpath, char *path) {
+    char dirname[32], basename[16];
+    
+    /** absolute path */
+    if (path[0] == '/') {
+        strcpy(newpath, path);
+    }
+    /** relative path */
+    else {
+        strcpy(newpath, cwd);
+        if (path[0] != 0) {
+            if (newpath[strlen(newpath)-1] != '/')
+                strcat(newpath, "/");
+            strcat(newpath, path);    
+        }
+        /** Resolve .. references */
+        splitName(newpath, dirname, basename);
+        if (!strcmp(basename, "..")) {
+            splitName(dirname, newpath, basename);
+        }
+    }
+}
+
+// copy t to s until space is reached
+// return location of delimiter+1 in t
+// if space not found, return t pointing to end of string
+// if s or t null, return null
+char *splitCmd(char *s, char *t, int max)
+{
+  int i = 0;
+  
+  if (s == 0 || t == 0)
+    return 0;
+
+  while (*t != 0 && i < max) {
+    *s++ = *t++;
+    i++;
+    if (*t == ' ') {
+        t++;
+        break;
+    }
+  }
+  *s = 0;
+    
+  return t;
+}
+
+/** splitName
+ * split the path into a dirname and a 
+ */
+void splitName(char *path, char *dirname, char *basename) {
+    int sep;
+    
+    sep = 0;
+    if (debug) pc.printf("%d\n", strlen(path));
+    for (int i=strlen(path)-1; i >= 0; i--) {
+        if (debug) pc.printf("- %c\n", path[i]);
+        sep = i;
+        if (path[i] == '/') break;
+    }
+    for (int j=0; j < sep; j++) {
+        if (debug) pc.printf("> %c\n", path[j]);
+        dirname[j] = path[j];
+        dirname[j+1] = 0;
+    }
+    for (int k=sep+1; k < strlen(path); k++) {
+        if (debug) pc.printf("* %c\n", path[k]);
+        basename[k-(sep+1)] = path[k];
+        basename[k-sep] = 0;    
+    }
+    if (debug) pc.printf("d:<%s> b:<%s>\n", dirname, basename);
+}
+
+/** ls
+ * lists files in the current working directory, 4 columns
+ */
+void ls(char *path) {
+    if (debug) pc.printf("%s\n", cwd);
+    DIR *d;
+    struct dirent *p;
+    
+    int count=0;
+    if ((d = opendir(path)) != NULL) {
+        while ((p = readdir(d)) != NULL) {
+            pc.printf("%12s", p->d_name);
+            if (count++ >= 3) {
+                count = 0;
+                pc.printf("\n");
+            }
+        }
+        pc.printf("\n");
+        if (count < 3)
+            pc.printf("\n");
+        closedir(d);
+    } else {
+        pc.printf("%s: No such directory\n", path);
+    }
+}
+
+/** cd
+ * changes current working directory
+ */
+void cd(char *path) {
+    strcpy(cwd, path);
+}
+
+/** pwd
+ * print current working directory
+ */
+void pwd() {
+    pc.printf("%s\n", cwd);
+}
+
+/** touch
+ * create an empty file
+ */
+void touch(char *path) {
+    FILE *fp;
+    if ((fp = fopen(path, "w")) != NULL) {
+        fclose(fp);
+    } else {
+        pc.printf("%s: No such file\n", path);
+    }
+} 
+
+/** head
+ * print the first 10 lines of a file
+ */
+void head(char *path) {
+    FILE *fp;
+    char line = 0;
+    
+    if ((fp = fopen(path, "r")) != NULL) {
+        while (!feof(fp) && line++ < 10) {
+            fgets(buf, 128, fp);
+            pc.printf("%s", buf);
+        }
+        fclose(fp);
+    } else {
+        pc.printf("%s: No such file\n", path);
+    }
+}
+
+/** cat
+ * display the content of a file
+ */
+void cat(char *path) {
+    FILE *fp;
+
+    if ((fp = fopen(path, "r")) != NULL) {
+        while (!feof(fp)) {
+            if (fgets(buf, 127, fp) != NULL)
+                pc.printf("%s", buf);
+        }
+        fclose(fp);
+    } else {
+        pc.printf("%s: No such file\n", path);
+    }
+}
+
+/** send
+ * Simple serial file transfer protocol
+ * Initiates escape sequence: ^A^B, sends filename, ^C, and then file
+ * contents followed by ^D
+ */
+void send(char *path) {
+    FILE *fp;
+    char dirname[32], basename[16];
+
+    if ((fp = fopen(path, "r")) != NULL) {
+        splitName(path, dirname, basename);
+        pc.printf("%c%c%s%c", 1, 2, basename, 3);
+        while (!feof(fp)) {
+            if (fgets(buf, 127, fp) != NULL)
+                pc.printf("%s", buf);
+        }
+        fclose(fp);
+        pc.printf("%c", 4);
+    } else {
+        pc.printf("%s: No such file\n", path);
+    }
+}
diff -r 000000000000 -r 826c6171fc1b UI/shell.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/UI/shell.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,6 @@
+#ifndef __SHELL_H
+#define __SHELL_H
+
+void shell(void);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b Watchdog.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Watchdog.lib	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/WiredHome/code/Watchdog/#2873f068f325
diff -r 000000000000 -r 826c6171fc1b debug.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/debug.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,10 @@
+#ifndef __DEBUG_H
+#define __DEBUG_H
+
+/** Debugging utilities */
+
+#include <stdio.h>
+
+#define WHERE(x) fprintf(stdout, "%d\n", __LINE__);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b globals.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/globals.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,10 @@
+#ifndef __GLOBALS_H
+#define __GLOBALS_H
+
+/** Global parameters */
+
+// Waypoint queue parameters
+#define MAXWPT    10
+#define ENDWPT    9999.0
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b logging/logging.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/logging/logging.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,122 @@
+#include "logging.h"
+#include "SDHCFileSystem.h"
+#include "SerialGraphicLCD.h"
+
+extern Serial pc;
+extern SerialGraphicLCD lcd;
+
+SDFileSystem sd(p5, p6, p7, p8, "log"); // mosi, miso, sclk, cs
+static FILE *logp;
+
+
+void clearState( SystemState *s ) {
+    s->millis = 0;
+    s->current = s->voltage = 0.0;
+    s->g[0] = s->g[1] = s->g[2] = 0;
+    s->gTemp = 0;
+    s->a[0] = s->a[1] = s->a[2] = 0;
+    s->m[0] = s->m[1] = s->m[2] = 0;
+    s->gHeading = s->cHeading = 0.0;
+    //s->roll = s->pitch = s->yaw =0.0;
+    s->gpsLatitude = s->gpsLongitude = s->gpsCourse = s->gpsHDOP = 0.0;
+    s->lrEncDistance = s->rrEncDistance = 0.0;
+    s->lrEncSpeed = s->rrEncSpeed = s->encHeading = 0.0;
+    s->estHeading = s->estLatitude = s->estLongitude = 0.0;
+    //s->estNorthing = s->estEasting = 
+    s->estX = s->estY = 0.0;
+    s->nextWaypoint = 0;
+    s->bearing = s->distance = 0.0;
+}
+
+//void logData( SystemState s, void (*logString)(char *s) ) {
+void logData( SystemState s ) {
+    char buf[256];
+
+    sprintf(buf, "%d,%.1f,%.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%.2f,,,,,%.6f,%.6f,%.1f,%.1f,%.1f,%d,%.7f,%.7f,%.2f,%.2f,%.1f,%.1f,%.6f,%.6f,,,%.4f,%.4f,%d,%.1f,%.3f,%.5f,%.5f,%.3f,%.3f,%.3f,%.3f\n",
+        s.millis,
+        s.current, s.voltage,
+        s.g[0], s.g[1], s.g[2],
+        s.gTemp,
+        s.a[0], s.a[1], s.a[2],
+        s.m[0], s.m[1], s.m[2],
+        s.gHeading, //s.cHeading,
+        //s.roll, s.pitch, s.yaw,
+        s.gpsLatitude, s.gpsLongitude, s.gpsCourse, s.gpsSpeed*0.44704, s.gpsHDOP, s.gpsSats, // convert gps speed to m/s
+        s.lrEncDistance, s.rrEncDistance, s.lrEncSpeed, s.rrEncSpeed, s.encHeading,
+        s.estHeading, s.estLatitude, s.estLongitude,
+        // s.estNorthing, s.estEasting, 
+        s.estX, s.estY,
+        s.nextWaypoint, s.bearing, s.distance, s.gbias, s.errAngle,
+        s.leftRanger, s.rightRanger, s.centerRanger,
+        s.crossTrackErr
+    );
+
+    if (logp)
+        fprintf(logp, buf);
+
+    return;    
+}
+
+
+FILE *openlog(char *prefix)
+{
+    FILE *fp = 0;
+    char myname[64];
+    
+    pc.printf("Opening file...\n");
+
+    while (fp == 0) {
+        if ((fp = fopen("/log/test.txt", "w")) == 0) {
+            pc.printf("Waiting for filesystem to come online...");
+            wait(0.200);
+            lcd.pos(0,1);
+            lcd.printf("%-16s", "Waiting for fs");
+        }
+    }    
+    fclose(fp);
+
+    for (int i = 0; i < 1000; i++) {
+        sprintf(myname, "/log/%s%03d.csv", prefix, i);
+        if ((fp = fopen(myname, "r")) == 0) {
+            break;
+        } else {
+            fclose(fp);
+        }
+    }
+    fp = fopen(myname, "w");
+    if (fp == 0) {
+        pc.printf("file write failed: %s\n", myname);
+    } else {
+    
+        // TODO -- set error message, get rid of writing to terminal
+        
+        //status = true;
+        pc.printf("opened %s for writing\n", myname);
+        lcd.pos(0,1);
+        lcd.printf("%-16s", myname);
+    }
+    
+    return fp;
+}
+
+
+// Find the next unused filename of the form logger##.csv where # is 0-9
+//
+bool initLogfile() 
+{    
+    bool status = false;
+    
+    logp = openlog("log");
+    
+    if (logp != 0) {
+        status = true;
+        fprintf(logp, "s.millis, s.current, s.voltage, s.gx, s.gy, s.gz, s.gTemp, s.ax, s.ay, s.az, s.mx, s.my, s.mz, s.gHeading, s.cHeading, s.roll, s.pitch, s.yaw, s.gpsLatitude, s.gpsLongitude, s.gpsCourse, s.gpsSpeed, s.gpsHDOP, s.lrEncDistance, s.rrEncDistance, s.lrEncSpeed, s.rrEncSpeed, s.encHeading, s.estHeading, s.estLatitude, s.estLongitude, s.estNorthing, s.estEasting, s.estX, s.estY, s.nextWaypoint, s.bearing, s.distance, s.gbias, s.errAngle, s.leftRanger, s.rightRanger, s.centerRanger, s.crossTrackErr\n");
+    }
+    
+    return status;
+}
+
+void closeLogfile(void)
+{
+    if (logp) fclose(logp);
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b logging/logging.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/logging/logging.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,15 @@
+#ifndef __LOGGING_H
+#define __LOGGING_H
+
+/** Data logging functions */
+
+#include "mbed.h"
+#include "SystemState.h"
+
+FILE *openlog(char *prefix);
+bool initLogfile(void);
+void clearState( SystemState *s );
+void logData( SystemState s );
+void closeLogfile(void);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b main.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1260 @@
+/** Code for "Data Bus" UGV entry for Sparkfun AVC 2012
+ *  http://www.bot-thoughts.com/
+ */
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// INCLUDES
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+#include <stdio.h>
+#include <math.h>
+#include "mbed.h"
+#include "globals.h"
+#include "Config.h"
+#include "Buttons.h"
+#include "Menu.h"
+//#include "lcd.h"
+#include "SerialGraphicLCD.h"
+#include "Bargraph.h"
+#include "GPSStatus.h"
+#include "logging.h"
+#include "shell.h"
+#include "Sensors.h"
+//#include "DCM.h"
+//#include "dcm_matrix.h"
+#include "kalman.h"
+#include "GPS.h"
+#include "Camera.h"
+#include "PinDetect.h"
+#include "Actuators.h"
+#include "IncrementalEncoder.h"
+#include "Steering.h"
+#include "Schedule.h"
+#include "GeoPosition.h"
+#include "Mapping.h"
+#include "SimpleFilter.h"
+#include "Beep.h"
+#include "util.h"
+#include "MAVlink/include/mavlink_bridge.h"
+#include "updater.h"
+
+#define LCD_FMT "%-20s" // used to fill a single line on the LCD screen
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// DEFINES
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+#define absf(x) (x *= (x < 0.0) ? -1 : 1)
+
+#define GPS_MIN_SPEED   2.0             // speed below which we won't trust GPS course
+#define GPS_MAX_HDOP    2.0             // HDOP above which we won't trust GPS course/position
+
+#define UPDATE_PERIOD 0.010             // update period in s
+#define UPDATE_PERIOD_MS 10             // update period in ms
+
+// Driver configuration parameters
+#define SONARLEFT_CHAN   0
+#define SONARRIGHT_CHAN  1
+#define IRLEFT_CHAN      2
+#define IRRIGHT_CHAN     3  
+#define TEMP_CHAN        4
+#define GYRO_CHAN        5
+
+// Chassis specific parameters
+#define WHEEL_CIRC 0.321537             // m; calibrated with 4 12.236m runs. Measured 13.125" or 0.333375m circumference
+#define WHEELBASE  0.290
+#define TRACK      0.280
+
+#define INSTRUMENT_CHECK    0
+#define AHRS_VISUALIZATION  1
+#define DISPLAY_PANEL       2
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// GLOBAL VARIABLES
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// OUTPUT
+DigitalOut confStatus(LED1);            // Config file status LED
+DigitalOut logStatus(LED2);             // Log file status LED
+DigitalOut gpsStatus(LED3);             // GPS fix status LED
+DigitalOut ahrsStatus(LED4);            // AHRS status LED
+//DigitalOut sonarStart(p18);             // Sends signal to start sonar array pings
+Beep speaker(p24);                      // Piezo speaker
+
+// INPUT
+Menu menu;
+Buttons keypad;
+
+// VEHICLE
+Steering steerCalc(TRACK, WHEELBASE);   // steering calculator
+
+// COMM
+Serial pc(USBTX, USBRX);                // PC usb communications
+SerialGraphicLCD lcd(p17, p18, SD_FW);  // Graphic LCD with summoningdark firmware
+//Serial *debug = &pc;
+
+// SENSORS
+Sensors sensors;                        // Abstraction of sensor drivers
+//DCM ahrs;                             // ArduPilot/MatrixPilot AHRS
+Serial *dev;                            // For use with bridge
+GPS gps(p26, p25, VENUS);               // gps
+
+FILE *camlog;                           // Camera log
+
+// Configuration
+Config config;                          // Persistent configuration
+                                        // Course Waypoints
+                                        // Sensor Calibration
+                                        // etc.
+
+// Timing
+Timer timer;                            // For main loop scheduling
+Ticker sched;                           // scheduler for interrupt driven routines
+
+// Overall system state (used for logging but also convenient for general use
+SystemState state[SSBUF];               // system state for logging, FIFO buffer
+unsigned char inState;                  // FIFO items enter in here
+unsigned char outState;                 // FIFO items leave out here
+bool ssBufOverrun = false;
+
+// GPS Variables
+unsigned long age = 0;                  // gps fix age
+
+// schedule for LED warning flasher
+Schedule blink;
+
+// Estimation & Navigation Variables
+GeoPosition dr_here;                    // Estimated position based on estimated heading
+GeoPosition gps_here;                   // current gps position
+Mapping mapper;
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// FUNCTION DEFINITIONS
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+void initFlasher(void);
+void initDR(void);
+int autonomousMode(void);
+void mavlinkMode(void);
+void servoCalibrate(void);
+void serialBridge(Serial &gps);
+int instrumentCheck(void);
+void displayData(int mode);
+int compassCalibrate(void);
+int compassSwing(void);
+int gyroSwing(void);
+int setBacklight(void);
+int reverseScreen(void);
+float gyroRate(unsigned int adc);
+float sonarDistance(unsigned int adc);
+float irDistance(unsigned int adc);
+float getVoltage(void);
+extern "C" void mbed_reset();
+
+extern unsigned int matrix_error;
+
+// If we don't close the log file, when we restart, all the written data
+// will be lost.  So we have to use a button to force mbed to close the
+// file and preserve the data.
+//
+
+int dummy(void)
+{
+    return 0;
+}
+
+
+// TODO: 3 move to GPS module
+/* GPS serial interrupt handler
+ */
+void gpsRecv() {
+    while (gps.serial.readable()) {
+        gpsStatus = !gpsStatus;
+        gps.nmea.encode(gps.serial.getc());
+        gpsStatus = !gpsStatus;
+    }
+}
+
+
+int resetMe()
+{
+    mbed_reset();
+    
+    return 0;
+}
+
+
+#define DISPLAY_CLEAR     0x01
+#define DISPLAY_SET_POS   0x08
+
+
+int main()
+{
+    // Send data back to the PC
+    pc.baud(115200);
+    lcd.baud(115200);
+    lcd.printf("test\n"); // hopefully force 115200 on powerup
+    lcd.clear();
+    wait(0.3);
+    lcd.printf("Data Bus mAGV V2");
+
+    fprintf(stdout, "Data Bus mAGV Control System\n");
+    
+    fprintf(stdout, "Initialization...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Initializing");
+    wait(0.5);
+    
+    gps.setUpdateRate(10);
+        
+    // Initialize status LEDs
+    ahrsStatus = 0;
+    gpsStatus = 0;
+    logStatus = 0;
+    confStatus = 0;
+
+    //ahrs.G_Dt = UPDATE_PERIOD; 
+
+    fprintf(stdout, "Loading configuration...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Load config");
+    wait(0.5);
+    if (config.load())                          // Load various configurable parameters, e.g., waypoints, declination, etc.
+        confStatus = 1;
+        
+    // Something here is jacking up the I2C stuff
+    initSteering();
+    initThrottle();
+    // initFlasher();                                   // Initialize autonomous mode flasher
+        
+    sensors.Compass_Calibrate(config.magOffset, config.magScale);
+    pc.printf("Declination: %.1f\n", config.declination);
+    pc.printf("Speed: escZero=%d escMax=%d top=%.1f turn=%.1f Kp=%.4f Ki=%.4f Kd=%.4f\n", 
+        config.escZero, config.escMax, config.topSpeed, config.turnSpeed, 
+        config.speedKp, config.speedKi, config.speedKd);
+    pc.printf("Steering: steerZero=%0.2f steerGain=%.1f gainAngle=%.1f\n", config.steerZero, config.steerGain, config.steerGainAngle);
+
+    // Convert lat/lon waypoints to cartesian
+    mapper.init(config.wptCount, config.wpt);
+    for (int w = 0; w < MAXWPT && w < config.wptCount; w++) {
+        mapper.geoToCart(config.wpt[w], &(config.cwpt[w]));
+        pc.printf("Waypoint #%d (%.4f, %.4f) lat: %.6f lon: %.6f\n", 
+                    w, config.cwpt[w]._x, config.cwpt[w]._y, config.wpt[w].latitude(), config.wpt[w].longitude());
+    }
+
+    // TODO: 3 print mag and gyro calibrations
+
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "GPS configuration   ");
+    gps.setType(config.gpsType);
+    gps.setBaud(config.gpsBaud);
+    fprintf(stdout, "GPS config: type=%d baud=%d\n", config.gpsType, config.gpsBaud);
+
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Nav configuration   ");
+    steerCalc.setIntercept(config.interceptDist);               // Setup steering calculator based on intercept distance
+    pc.printf("Intercept distance: %.1f\n", config.interceptDist);
+    pc.printf("Waypoint distance: %.1f\n", config.waypointDist);
+    pc.printf("Brake distance: %.1f\n", config.brakeDist);
+    pc.printf("Min turn radius: %.3f\n", config.minRadius);
+    
+    fprintf(stdout, "Calculating offsets...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Offset calculation  ");
+    wait(0.5);
+    // TODO: 3 Really need to give the gyro more time to settle
+    sensors.Calculate_Offsets();
+
+    fprintf(stdout, "Starting GPS...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Start GPS           ");
+    wait(0.5);
+    // TODO: 3 move this to GPS module
+    gps.serial.attach(gpsRecv, Serial::RxIrq);
+    // TODO: 3 enable and process GSV as bar graph
+    //gps.gsvMessage(false);
+    //gps.gsaMessage(true);
+
+    fprintf(stdout, "Starting Scheduler...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Start scheduler     ");
+    wait(0.5);
+    // Startup sensor/AHRS ticker; update every 10ms = 100hz
+    restartNav();
+    sched.attach(&update, UPDATE_PERIOD);
+
+/*
+    fprintf(stdout, "Starting Camera...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Start Camera        ");
+    wait(0.5);
+    cam.start();
+*/
+
+    // Let's try setting serial IRQs lower and see if that alleviates issues with I2C reads and AHRS reads
+    //NVIC_SetPriority(UART0_IRQn, 1); // USB
+    //NVIC_SetPriority(UART1_IRQn, 2); // GPS p25,p26
+    //NVIC_SetPriority(UART3_IRQn, 3); // LCD p17,p18
+       
+    // Insert menu system here w/ timeout
+    //bool autoBoot=false;
+
+    //speaker.beep(3000.0, 0.2); // non-blocking
+
+    keypad.init();
+
+    // Initialize LCD graphics
+    Bargraph::lcd = &lcd;   
+    Bargraph v(1, 40, 15, 'V');
+    v.calibrate(6.3, 8.4);
+    Bargraph a(11, 40, 15, 'A');
+    a.calibrate(0, 15.0);
+    Bargraph g1(21, 40, 15, 'G');
+    g1.calibrate(0, 10);
+    Bargraph g2(31, 40, 15, 'H');
+    g2.calibrate(4.0, 0.8);
+    //GPSStatus g2(21, 12);
+    //GPSStatus::lcd = &lcd;
+    
+    // Setup LCD Input Menu
+    menu.add("Auto mode", &autonomousMode);
+    menu.add("Instruments", &instrumentCheck);
+    menu.add("Calibrate", &compassCalibrate);
+    menu.add("Compass Swing", &compassSwing);
+    menu.add("Gyro Calib", &gyroSwing);
+    //menu.sdd("Reload Config", &loadConfig);
+    menu.add("Backlight", &setBacklight);
+    menu.add("Reverse", &reverseScreen);
+    menu.add("Reset", &resetMe);
+   
+    char cmd;
+    bool printMenu = true;
+    bool printLCDMenu = true;
+    
+    timer.start();
+    timer.reset();
+
+    int thisUpdate = timer.read_ms();    
+    int nextUpdate = thisUpdate;
+    //int hdgUpdate = nextUpdate;
+
+    while (1) {
+
+        /*
+        if (timer.read_ms() > hdgUpdate) {
+            fprintf(stdout, "He=%.3f %.5f\n", kfGetX(0), kfGetX(1));
+            hdgUpdate = timer.read_ms() + 100;
+        }*/
+
+        if ((thisUpdate = timer.read_ms()) > nextUpdate) {
+            //fprintf(stdout, "Updating...\n");
+            v.update(sensors.voltage);
+            a.update(sensors.current);
+            g1.update((float) gps.nmea.sat_count());
+            g2.update(gps.hdop);
+            lcd.posXY(60, 22);
+            lcd.printf("%.2f", state[inState].rightRanger);
+            lcd.posXY(60, 32);
+            lcd.printf("%.2f", state[inState].leftRanger);
+            lcd.posXY(60, 42);
+            lcd.printf("%5.1f", state[inState].estHeading);
+            lcd.posXY(60, 52);
+            lcd.printf("%.3f", state[inState].gpsCourse);
+            nextUpdate = thisUpdate + 2000;
+            // TODO: 3 address integer overflow
+            // TODO: 3 display scheduler() timing
+        }
+        
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            printLCDMenu = true;
+            //causes issue with servo library
+            //speaker.beep(3000.0, 0.1); // non-blocking
+            switch (keypad.which) {
+                case NEXT_BUTTON:
+                    menu.next();
+                    break;
+                case PREV_BUTTON:
+                    menu.prev();
+                    break;
+                case SELECT_BUTTON:
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", menu.getItemName());
+                    menu.select();
+                    printMenu = true;
+                    break;
+                default:
+                    printLCDMenu = false;
+                    break;
+            }//switch  
+            keypad.pressed = false;
+        }// if (keypad.pressed)
+
+            
+        if (printLCDMenu) {
+            lcd.pos(0,0);
+            lcd.printf("< %-14s >", menu.getItemName());
+            lcd.pos(0,1);
+            lcd.printf(LCD_FMT, "Ready.");
+            lcd.posXY(50, 22);
+            lcd.printf("R");
+            lcd.rect(58, 20, 98, 30, true);
+            wait(0.01);
+            lcd.posXY(50, 32);
+            lcd.printf("L");
+            lcd.rect(58, 30, 98, 40, true);
+            wait(0.01);
+            lcd.posXY(50, 42);
+            lcd.printf("H");
+            lcd.rect(58, 40, 98, 50, true);
+            wait(0.01);
+            lcd.posXY(44,52);
+            lcd.printf("GH");
+            lcd.rect(58, 50, 98, 60, true);
+            v.init();
+            a.init();
+            g1.init();
+            g2.init();
+            printLCDMenu = false;
+        }
+        
+/*      if (autoBoot) {
+            autoBoot = false;
+            cmd = 'a';
+        } else {*/
+        
+        if (printMenu) {
+            int i=0;
+            fprintf(stdout, "\n==============\nData Bus Menu\n==============\n");
+            fprintf(stdout, "%d) Autonomous mode\n", i++);
+            fprintf(stdout, "%d) Bridge serial to GPS\n", i++);
+            fprintf(stdout, "%d) Calibrate compass\n", i++);
+            fprintf(stdout, "%d) Swing compass\n", i++);
+            fprintf(stdout, "%d) Gyro calibrate\n", i++);
+            fprintf(stdout, "%d) Instrument check\n", i++);
+            fprintf(stdout, "%d) Display AHRS\n", i++);
+            fprintf(stdout, "%d) Mavlink mode\n", i++);
+            fprintf(stdout, "%d) Shell\n", i++);
+            fprintf(stdout, "R) Reset\n");
+            fprintf(stdout, "\nSelect from the above: ");
+            fflush(stdout);
+            printMenu = false;
+        }
+
+
+        // Basic functional architecture
+        // SENSORS -> FILTERS -> AHRS -> POSITION -> NAVIGATION -> CONTROL | INPUT/OUTPUT | LOGGING
+        // SENSORS (for now) are polled out of AHRS via interrupt every 10ms
+        //
+        // no FILTERing in place right now
+        // if we filter too heavily we get lag. At 30mph = 14m/s a sensor lag
+        // of only 10ms means the estimate is 140cm behind the robot
+        //
+        // POSITION and NAVIGATION should probably always be running
+        // log file can have different entry type per module, to be demultiplexed on the PC
+        //
+        // Autonomous mode engages CONTROL outputs
+        //
+        // I/O mode could be one of: MAVlink, serial bridge (gps), sensor check, shell, log to serial
+        // Or maybe shell should be the main control for different output modes
+        //
+        // LOGGING can be turned on or off, probably best to start with it engaged
+        // and then disable from user panel or when navigation is ended
+
+        if (pc.readable()) {
+            cmd = pc.getc();
+            fprintf(stdout, "%c\n", cmd);
+            printMenu = true;
+            printLCDMenu = true;
+            
+            switch (cmd) {
+                case 'R' :
+                    resetMe();
+                    break;
+                case '0' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", menu.getItemName(0));
+                    autonomousMode();
+                    break;
+                case '1' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", "Serial bridge");
+                    lcd.pos(0,1);
+                    lcd.printf(LCD_FMT, "Standby.");
+                    gps.gsvMessage(true);
+                    gps.gsaMessage(true);
+                    serialBridge(gps.serial);
+                    gps.gsvMessage(false);
+                    gps.gsaMessage(false);                        
+                    break;
+                case '2' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", menu.getItemName(1));
+                    compassCalibrate();
+                    break;
+                case '3' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", menu.getItemName(2));
+                    compassSwing();
+                    break;
+                case '4' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", menu.getItemName(2));
+                    gyroSwing();
+                    break;
+                case '5' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", "Instruments");
+                    lcd.pos(0,1);
+                    lcd.printf(LCD_FMT, "Standby.");
+                    displayData(INSTRUMENT_CHECK);
+                    break;
+                case '6' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", "AHRS Visual'n");
+                    lcd.pos(0,1);
+                    lcd.printf(LCD_FMT, "Standby.");
+                    displayData(AHRS_VISUALIZATION);
+                    break;
+                case '7' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", "Mavlink mode");
+                    lcd.pos(0,1);
+                    lcd.printf(LCD_FMT, "Standby.");
+                    mavlinkMode();
+                    break;
+                case '8' :
+                    lcd.pos(0,0);
+                    lcd.printf(">>%-14s", "Shell");
+                    lcd.pos(0,1);
+                    lcd.printf(LCD_FMT, "Standby.");
+                    shell();
+                    break;
+                default :
+                    break;
+            } // switch        
+
+        } // if (pc.readable())
+
+    } // while
+
+}
+
+
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// INITIALIZATION ROUTINES
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+    
+void initFlasher()
+{ 
+    // Set up flasher schedule; 3 flashes every 80ms
+    // for 80ms total, with a 9x80ms period
+    blink.max(9);
+    blink.scale(80);
+    blink.mode(Schedule::repeat);
+    blink.set(0, 1);  blink.set(2, 1);  blink.set(4, 1);
+}
+
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// OPERATIONAL MODE FUNCTIONS
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+int autonomousMode()
+{
+    bool goGoGo = false;                    // signal to start moving
+    bool navDone;                      // signal that we're done navigating
+    extern int tSensor, tGPS, tAHRS, tLog;
+
+    // TODO: 3 move to main?
+    // Navigation
+
+    goGoGo = false;
+    navDone = false;
+    keypad.pressed = false;
+    //bool started = false;  // flag to indicate robot has exceeded min speed.
+    
+    if (initLogfile()) logStatus = 1;                           // Open the log file in sprintf format string style; numbers go in %d
+    wait(0.2);
+
+    gps.setNmeaMessages(true, true, false, false, true, false); // enable GGA, GSA, RMC
+    gps.serial.attach(gpsRecv, Serial::RxIrq);
+
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Select starts.");
+    wait(1.0);
+
+    timer.reset();
+    timer.start();
+    wait(0.1);
+    
+    // Initialize logging buffer
+    // Needs to happen after we've reset the millisecond timer and after
+    // the schedHandler() fires off at least once more with the new time
+    inState = outState = 0;    
+    
+    // Tell the navigation / position estimation stuff to reset to starting waypoint
+    restartNav();
+                
+    // Main loop
+    //
+    while(navDone == false) {
+
+        //////////////////////////////////////////////////////////////////////////////
+        // USER INPUT
+        //////////////////////////////////////////////////////////////////////////////
+
+        // Button state machine
+        // if we've not started going, button starts us
+        // if we have started going, button stops us
+        // but only if we've released it first
+        //
+        // set throttle only if goGoGo set
+        if (goGoGo) {
+            /** acceleration curve */
+            /*
+            if (go.ticked(timer.read_ms())) {
+                throttle = go.get() / 1000.0;
+                //fprintf(stdout, "throttle: %0.3f\n", throttle.read());
+            }
+            */
+            
+            // TODO: 1 Add additional condition of travel for N meters before
+            // the HALT button is armed
+            
+            if (keypad.pressed == true) { // && started
+                fprintf(stdout, ">>>>>>>>>>>>>>>>>>>>>>> HALT\n");
+                lcd.pos(0,1);
+                lcd.printf(LCD_FMT, "HALT.");
+                navDone = true;
+                goGoGo = false;
+                keypad.pressed = false;
+                endRun();
+            }
+        } else {
+            if (keypad.pressed == true) {
+                fprintf(stdout, ">>>>>>>>>>>>>>>>>>>>>>> GO GO GO\n");
+                lcd.pos(0,1);
+                lcd.printf(LCD_FMT, "GO GO GO!");
+                goGoGo = true;
+                keypad.pressed = false;
+                //restartNav();
+                beginRun();
+                // Doing this for collecting step response, hopefully an S curve... we'll see.
+                //throttle = config.escMax;
+                // TODO: 2 Improve encapsulation of the scheduler
+                // TODO: 2 can we do something clever with GPS position estimate since we know where we're starting?
+                // E.g. if dist to wpt0 < x then initialize to wpt0 else use gps
+            }
+        }        
+
+        // Are we at the last waypoint?
+        // 
+        if (state[inState].nextWaypoint == config.wptCount) {
+            fprintf(stdout, "Arrived at final destination. Done.\n");
+            //causes issue with servo library
+            //speaker.beep(3000.0, 1.0); // non-blocking
+            lcd.pos(0,1);
+            lcd.printf(LCD_FMT, "Arrived. Done.");
+            navDone = true;
+            endRun();
+        }
+
+        //////////////////////////////////////////////////////////////////////////////
+        // LOGGING
+        //////////////////////////////////////////////////////////////////////////////
+        // sensor reads are happening in the schedHandler();
+        // Are there more items to come out of the log buffer?
+        // Since this could take anywhere from a few hundred usec to
+        // 150ms, we run it opportunistically and use a buffer. That way
+        // the sensor updates, calculation, and control can continue to happen
+        if (outState != inState) {
+            logStatus = !logStatus;         // log indicator LED
+            //fprintf(stdout, "FIFO: in=%d out=%d\n", inState, outState);
+            if (ssBufOverrun) {
+                fprintf(stdout, ">>> SystemState Buffer Overrun Condition\n");
+                ssBufOverrun = false;
+            }
+            // do we need to disable interrupts briefly to prevent a race
+            // condition with schedHandler() ?
+            int out=outState;               // in case we're interrupted this 'should' be atomic
+            outState++;                     // increment
+            outState &= SSBUF;              // wrap
+            logData( state[out] );          // log state data to file
+            logStatus = !logStatus;         // log indicator LED
+            
+            //fprintf(stdout, "Time Stats\n----------\nSensors: %d\nGPS: %d\nAHRS: %d\nLog: %d\n----------\nTotal: %d",
+            //        tSensor, tGPS, tAHRS, tLog, tSensor+tGPS+tAHRS+tLog);
+        }
+
+    } // while
+    
+    closeLogfile();
+    logStatus = 0;
+    fprintf(stdout, "Completed, file saved.\n");
+    wait(2); // wait from last printout
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Done. Saved.");
+    wait(2);        
+
+    ahrsStatus = 0;
+    gpsStatus = 0;
+    //confStatus = 0;
+    //flasher = 0;
+
+    gps.gsaMessage(false);
+    gps.gsvMessage(false);
+
+    return 0;
+} // autonomousMode
+
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// UTILITY FUNCTIONS
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+
+int compassCalibrate()
+{
+    bool done=false;
+    int m[3];
+    FILE *fp;
+    
+    fprintf(stdout, "Entering compass calibration in 2 seconds.\nLaunch _3DScatter Processing app now... type e to exit\n");
+    lcd.pos(0,1);
+
+    lcd.printf(LCD_FMT, "Starting...");
+
+    fp = openlog("cal");
+
+    wait(2);
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Select exits");
+    timer.reset();
+    timer.start();
+    while (!done) {
+    
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            done = true;
+        }
+        
+        while (pc.readable()) {
+            if (pc.getc() == 'e') {
+                done = true;
+                break;
+            }
+        }
+        int millis = timer.read_ms();
+        if ((millis % 100) == 0) {
+            sensors.getRawMag(m);
+
+            // Correction
+            // Let's see how our ellipsoid looks after scaling and offset            
+            /*
+            float mag[3];
+            mag[0] = ((float) m[0] - M_OFFSET_X) * 0.5 / M_SCALE_X;
+            mag[1] = ((float) m[1] - M_OFFSET_Y) * 0.5 / M_SCALE_Y;
+            mag[2] = ((float) m[2] - M_OFFSET_Z) * 0.5 / M_SCALE_Z;  
+            */
+            
+            bool skipIt = false;
+            for (int i=0; i < 3; i++) {
+                if (abs(m[i]) > 1024) skipIt = true;
+            }
+            if (!skipIt) {
+                fprintf(stdout, "%c%d %d %d \r\n", 0xDE, m[0], m[1], m[2]);
+                fprintf(fp, "%d, %d, %d\n", m[0], m[1], m[2]);
+            }
+        }
+    }
+    if (fp) {
+        fclose(fp);
+        lcd.pos(0,1);
+        lcd.printf(LCD_FMT, "Done. Saved.");
+        wait(2);
+    }
+
+    return 0;
+}
+
+// Gather gyro data using turntable equipped with dual channel
+// encoder. Use onboard wheel encoder system. Left channel
+// is the index (0 degree) mark, while the right channel
+// is the incremental encoder.  Can then compare gyro integrated
+// heading with machine-reported heading
+//
+// Note: some of this code is identical to the compassSwing() code.
+//
+int gyroSwing()
+{
+    FILE *fp;
+
+    // Timing is pretty critical so just in case, disable serial processing from GPS
+    gps.serial.attach(NULL, Serial::RxIrq);
+
+    fprintf(stdout, "Entering gyro swing...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Starting...");
+    wait(2);
+    fp = openlog("gy");
+    wait(2);
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Begin. Select exits.");
+
+    fprintf(stdout, "Begin clockwise rotation, varying rpm... press select to exit\n");
+
+    timer.reset();
+    timer.start();
+
+    sensors.rightTotal = 0; // reset total
+    sensors._right.read();  // easiest way to reset the heading counter
+    
+    while (1) {
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            break;
+        }
+
+        // Print out data
+        // fprintf(stdout, "%d,%d,%d,%d,%d\n", timer.read_ms(), heading, sensors.g[0], sensors.g[1], sensors.g[2]);
+        // sensors.rightTotal gives us each tick of the machine, multiply by 2 for cumulative heading, which is easiest
+        // to compare with cumulative integration of gyro (rather than dealing with 0-360 degree range and modulus and whatnot
+        if (fp) fprintf(fp, "%d,%d,%d,%d,%d,%d\n", timer.read_ms(), 2*sensors.rightTotal, sensors.g[0], sensors.g[1], sensors.g[2], sensors.gTemp);
+        wait(0.200);
+    }    
+    if (fp) {
+        fclose(fp);
+        lcd.pos(0,1);
+        lcd.printf(LCD_FMT, "Done. Saved.");
+        fprintf(stdout, "Data collection complete.\n");
+        wait(2);
+    }
+    
+    keypad.pressed = false;
+
+    return 0;
+}
+
+
+// Swing compass using turntable equipped with dual channel
+// encoder. Use onboard wheel encoder system. Left channel
+// is the index (0 degree) mark, while the right channel
+// is the incremental encoder.
+//
+// Note: much of this code is identical to the gyroSwing() code.
+//
+int compassSwing()
+{
+    int revolutions=5;
+    int heading=0;
+    int leftCount = 0;
+    FILE *fp;
+    // left is index track
+    // right is encoder track
+
+    fprintf(stdout, "Entering compass swing...\n");
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Starting...");
+    wait(2);
+    fp = openlog("sw");
+    wait(2);
+    lcd.pos(0,1);
+    lcd.printf(LCD_FMT, "Ok. Begin.");
+
+    fprintf(stdout, "Begin clockwise rotation... exit after %d revolutions\n", revolutions);
+
+    timer.reset();
+    timer.start();
+
+    // wait for index to change
+    while ((leftCount += sensors._left.read()) < 2) {
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            break;    
+        }
+    }
+    fprintf(stdout, ">>>> Index detected. Starting data collection\n");
+    leftCount = 0;
+    lcd.pos(0,1);
+    lcd.printf("%1d %-14s", revolutions, "revs left");
+
+    sensors._right.read(); // easiest way to reset the heading counter
+    
+    while (revolutions > 0) {
+        int encoder;
+
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            break;
+        }
+               
+        // wait for state change
+        while ((encoder = sensors._right.read()) == 0) {
+            if (keypad.pressed) {
+                keypad.pressed = false;
+                break;
+            }
+        }
+        heading += 2*encoder;                          // encoder has resolution of 2 degrees
+        if (heading >= 360) heading -= 360;
+                
+        // when index is 1, reset the heading and decrement revolution counter
+        // make sure we don't detect the index mark until after the first several
+        // encoder pulses.  Index is active low
+        if ((leftCount += sensors._left.read()) > 1) {
+            // check for error in heading?
+            leftCount = 0;
+            revolutions--;
+            fprintf(stdout, ">>>>> %d left\n", revolutions); // we sense the rising and falling of the index so /2
+            lcd.pos(0,1);
+            lcd.printf("%1d %-14s", revolutions, "revs left");
+        }
+        
+        float heading2d = 180 * atan2((float) sensors.mag[1], (float) sensors.mag[0]) / PI;
+        // Print out data
+        //getRawMag(m);
+        fprintf(stdout, "%d %.4f\n", heading, heading2d);
+
+//        int t1=t.read_us();
+        if (fp) fprintf(fp, "%d, %d, %.2f, %.4f, %.4f, %.4f\n", 
+                            timer.read_ms(), heading, heading2d, sensors.mag[0], sensors.mag[1], sensors.mag[2]);
+//        int t2=t.read_us();
+//        fprintf(stdout, "dt=%d\n", t2-t1);
+    }    
+    if (fp) {
+        fclose(fp);
+        lcd.pos(0,1);
+        lcd.printf(LCD_FMT, "Done. Saved.");
+        fprintf(stdout, "Data collection complete.\n");
+        wait(2);
+    }
+    
+    keypad.pressed = false;
+        
+    return 0;
+}
+
+void servoCalibrate() 
+{
+}
+
+void bridgeRecv()
+{
+    while (dev && dev->readable()) {
+        pc.putc(dev->getc());
+    }
+}
+
+void serialBridge(Serial &serial)
+{
+    char x;
+    int count = 0;
+    bool done=false;
+
+    fprintf(stdout, "\nEntering serial bridge in 2 seconds, +++ to escape\n\n");
+    //gps.setNmeaMessages(true, true, true, false, true, false); // enable GGA, GSA, GSV, RMC
+    gps.setNmeaMessages(true, false, false, false, true, false); // enable only GGA, RMC
+    wait(2.0);
+    //dev = &gps;
+    serial.attach(NULL, Serial::RxIrq);
+    while (!done) {
+        if (pc.readable()) {
+            x = pc.getc();
+            // escape sequence
+            if (x == '+') {
+                if (++count >= 3) done=true;
+            } else {
+                count = 0;
+            }
+            serial.putc(x);
+        }
+        if (serial.readable()) {
+            pc.putc(serial.getc());
+        }
+    }
+}
+
+/* to be called from panel menu
+ */
+int instrumentCheck(void) {
+    displayData(INSTRUMENT_CHECK);
+    return 0;
+}
+
+/* Display data
+ * mode determines the type of data and format
+ * INSTRUMENT_CHECK   : display readings of various instruments
+ * AHRS_VISUALIZATION : display data for use by AHRS python visualization script
+ */
+ 
+void displayData(int mode)
+{
+    bool done = false;
+
+    lcd.clear();
+
+    // Init GPS
+    gps.setNmeaMessages(true, false, false, false, true, false); // enable GGA, GSA, RMC
+    gps.serial.attach(gpsRecv, Serial::RxIrq);
+    gps.nmea.reset_ready();    
+
+    keypad.pressed = false;  
+    
+    timer.reset();
+    timer.start();
+      
+    fprintf(stdout, "press e to exit\n");
+    while (!done) {
+        int millis = timer.read_ms();
+
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            done=true;
+        }
+        
+        while (pc.readable()) {
+            if (pc.getc() == 'e') {
+                done = true;
+                break;
+            }
+        }
+
+/*        
+        if (mode == AHRS_VISUALIZATION && (millis % 100) == 0) {
+
+            fprintf(stdout, "!ANG:%.1f,%.1f,%.1f\r\n", ToDeg(ahrs.roll), ToDeg(ahrs.pitch), ToDeg(ahrs.yaw));
+
+        } else */      
+        
+        if (mode == INSTRUMENT_CHECK) {
+
+            if ((millis % 1000) == 0) {
+
+                fprintf(stdout, "update() time = %.3f msec\n", getUpdateTime() / 1000.0);
+                fprintf(stdout, "Rangers: L=%.2f R=%.2f C=%.2f", sensors.leftRanger, sensors.rightRanger, sensors.centerRanger);
+                fprintf(stdout, "\n");
+                //fprintf(stdout, "ahrs.MAG_Heading=%4.1f\n",  ahrs.MAG_Heading*180/PI);
+                fprintf(stdout, "raw m=(%d, %d, %d)\n", sensors.m[0], sensors.m[1], sensors.m[2]);
+                fprintf(stdout, "m=(%2.3f, %2.3f, %2.3f) %2.3f\n", sensors.mag[0], sensors.mag[1], sensors.mag[2],
+                        sqrt(sensors.mag[0]*sensors.mag[0] + sensors.mag[1]*sensors.mag[1] + sensors.mag[2]*sensors.mag[2] ));
+                fprintf(stdout, "g=(%4d, %4d, %4d) %d\n", sensors.g[0], sensors.g[1], sensors.g[2], sensors.gTemp);
+                fprintf(stdout, "gc=(%.1f, %.1f, %.1f)\n", sensors.gyro[0], sensors.gyro[1], sensors.gyro[2]);
+                fprintf(stdout, "a=(%5d, %5d, %5d)\n", sensors.a[0], sensors.a[1], sensors.a[2]);
+                fprintf(stdout, "estHdg=%.2f\n", state[inState].estHeading);
+                //fprintf(stdout, "roll=%.2f pitch=%.2f yaw=%.2f\n", ToDeg(ahrs.roll), ToDeg(ahrs.pitch), ToDeg(ahrs.yaw));
+                fprintf(stdout, "speed: left=%.3f  right=%.3f\n", sensors.lrEncSpeed, sensors.rrEncSpeed);
+                fprintf(stdout, "gps=(%.6f, %.6f, %.1f, %.1f, %.1f, %d)\n", gps_here.latitude(), gps_here.longitude(),
+                    gps.nmea.f_course(), gps.nmea.f_speed_mps(), gps.hdop, gps.nmea.sat_count());
+                fprintf(stdout, "v=%.2f  a=%.3f\n", sensors.voltage, sensors.current);
+                fprintf(stdout, "\n");
+                
+            }
+
+            if ((millis % 3000) == 0) {
+
+                lcd.pos(0,1);
+                //lcd.printf("H=%4.1f   ", ahrs.MAG_Heading*180/PI);
+                //wait(0.1);
+                lcd.pos(0,2);
+                lcd.printf("G=%4.1f,%4.1f,%4.1f    ", sensors.gyro[0], sensors.gyro[1], sensors.gyro[2]);
+                wait(0.1);
+                lcd.pos(0,3);
+                lcd.printf("La=%11.6f HD=%1.1f  ", gps_here.latitude(), gps.hdop);
+                wait(0.1);
+                lcd.pos(0,4);
+                lcd.printf("Lo=%11.6f Sat=%-2d  ", gps_here.longitude(), gps.nmea.sat_count());
+                wait(0.1);
+                lcd.pos(0,5);
+                lcd.printf("V=%5.2f A=%5.3f  ", sensors.voltage, sensors.current);
+                
+            }
+        }
+    
+    } // while !done
+    // clear input buffer
+    while (pc.readable()) pc.getc();
+    lcd.clear();
+    ahrsStatus = 0;
+    gpsStatus = 0;
+}
+
+
+// TODO: 3 move Mavlink into main (non-interrupt) loop along with logging
+// possibly also buffered if necessary
+
+void mavlinkMode() {
+    uint8_t system_type = MAV_FIXED_WING;
+    uint8_t autopilot_type = MAV_AUTOPILOT_GENERIC;
+    //int count = 0;
+    bool done = false;
+    
+    mavlink_system.sysid = 100; // System ID, 1-255
+    mavlink_system.compid = 200; // Component/Subsystem ID, 1-255
+
+    //mavlink_attitude_t mav_attitude;
+    //mavlink_sys_status_t mav_stat;
+    mavlink_vfr_hud_t mav_hud;
+ 
+    //mav_stat.mode = MAV_MODE_MANUAL;
+    //mav_stat.status = MAV_STATE_STANDBY;
+    //mav_stat.vbat = 8400;
+    //mav_stat.battery_remaining = 1000;
+
+    mav_hud.airspeed = 0.0;
+    mav_hud.groundspeed = 0.0;
+    mav_hud.throttle = 0;
+
+    fprintf(stdout, "Entering MAVlink mode; reset the MCU to exit\n\n");
+
+    gps.gsvMessage(true);
+    gps.gsaMessage(true);
+    gps.serial.attach(gpsRecv, Serial::RxIrq);
+    
+    while (done == false) {
+
+        if (keypad.pressed == true) { // && started
+            keypad.pressed = false;
+            done = true;
+        }
+
+        int millis = timer.read_ms();
+      
+        if ((millis % 1000) == 0) {
+
+            mav_hud.heading = 0.0; //ahrs.parser.yaw;
+            
+            mavlink_msg_attitude_send(MAVLINK_COMM_0, millis*1000, 
+                0.0, //ToDeg(ahrs.roll),
+                0.0, //ToDeg(ahrs.pitch),
+                0.0, //ToDeg(ahrs.yaw), TODO: 3 fix this to use current estimate
+                0.0, // rollspeed
+                0.0, // pitchspeed
+                0.0  // yawspeed
+            );
+
+            mav_hud.groundspeed = sensors.encSpeed;
+            mav_hud.groundspeed *= 2.237; // convert to mph
+            //mav_hud.heading = compassHeading();
+
+            mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, 
+                    mav_hud.groundspeed, 
+                    mav_hud.groundspeed, 
+                    mav_hud.heading, 
+                    mav_hud.throttle, 
+                    0.0, // altitude
+                    0.0  // climb
+            );
+
+            mavlink_msg_heartbeat_send(MAVLINK_COMM_0, system_type, autopilot_type);
+            mavlink_msg_sys_status_send(MAVLINK_COMM_0,
+                    MAV_MODE_MANUAL,
+                    MAV_NAV_GROUNDED,
+                    MAV_STATE_STANDBY,
+                    0.0, // load
+                    (uint16_t) (sensors.voltage * 1000),
+                    1000, // TODO: 3 fix batt remaining
+                    0 // packet drop
+            );
+            
+            wait(0.001);
+        } // millis % 1000
+
+        if (gps.nmea.rmc_ready() && gps.nmea.gga_ready()) {
+            char gpsdate[32], gpstime[32];
+
+            gps.process(gps_here, gpsdate, gpstime);
+            gpsStatus = (gps.hdop > 0.0 && gps.hdop < 3.0) ? 1 : 0;
+
+            mavlink_msg_gps_raw_send(MAVLINK_COMM_0, millis*1000, 3, 
+                gps_here.latitude(), 
+                gps_here.longitude(), 
+                0.0, // altitude
+                gps.nmea.f_hdop()*100.0, 
+                0.0, // VDOP
+                mav_hud.groundspeed, 
+                mav_hud.heading
+            );
+                
+            mavlink_msg_gps_status_send(MAVLINK_COMM_0, gps.nmea.sat_count(), 0, 0, 0, 0, 0);
+
+            gps.nmea.reset_ready();
+                
+        } //gps
+
+        //mavlink_msg_attitude_send(MAVLINK_COMM_0, millis*1000, mav_attitude.roll, mav_attitude.pitch, mav_attitude.yaw, 0.0, 0.0, 0.0);
+        //mavlink_msg_sys_status_send(MAVLINK_COMM_0, mav_stat.mode, mav_stat.nav_mode, mav_stat.status, mav_stat.load,
+        //                            mav_stat.vbat, mav_stat.battery_remaining, 0);
+    }
+
+    gps.serial.attach(NULL, Serial::RxIrq);
+    gps.gsvMessage(false);
+    gps.gsaMessage(false);
+    fprintf(stdout, "\n");
+    
+    return;
+}
+
+
+int setBacklight(void) {
+    Menu bmenu;
+    bool done = false;
+    bool printUpdate = false;
+    static int backlight=100;
+    
+    lcd.pos(0,0);
+    lcd.printf(LCD_FMT, ">> Backlight");
+
+    while (!done) {
+        if (keypad.pressed) {
+            keypad.pressed = false;
+            printUpdate = true;
+            switch (keypad.which) {
+                case NEXT_BUTTON:
+                    backlight+=5;
+                    if (backlight > 100) backlight = 100;
+                    lcd.backlight(backlight);
+                    break;
+                case PREV_BUTTON:
+                    backlight-=5;
+                    if (backlight < 0) backlight = 0;
+                    lcd.backlight(backlight);
+                    break;
+                case SELECT_BUTTON:
+                    done = true;
+                    break;    
+            }
+        }
+        if (printUpdate) {
+            printUpdate = false;
+            lcd.pos(0,1);
+            lcd.printf("%3d%%%-16s", backlight, "");
+        }
+    }
+    
+    return 0;
+}
+
+int reverseScreen(void) {
+    lcd.reverseMode();
+    
+    return 0;
+}
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+// ADC CONVERSION FUNCTIONS
+///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// returns distance in m for Sharp GP2YOA710K0F
+// to get m and b, I wrote down volt vs. dist by eyeballin the
+// datasheet chart plot. Then used Excel to do linear regression
+//
+float irDistance(unsigned int adc)
+{
+    float b = 1.0934; // Intercept from Excel
+    float m = 1.4088; // Slope from Excel
+
+    return m / (((float) adc) * 4.95/4096 - b);
+}
diff -r 000000000000 -r 826c6171fc1b mbed.bld
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/737756e0b479
diff -r 000000000000 -r 826c6171fc1b updater.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/updater.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,599 @@
+#include "Config.h"
+#include "Actuators.h"
+#include "Sensors.h"
+#include "SystemState.h"
+#include "GPS.h"
+#include "Steering.h"
+#include "Servo.h"
+#include "Mapping.h"
+#include "CartPosition.h"
+#include "GeoPosition.h"
+#include "kalman.h"
+
+#define _x_ 0
+#define _y_ 1
+#define _z_ 2
+
+// Every ...
+//  10ms (100Hz) -- update gyro, encoders; update AHRS; update navigation; set log data
+//  10ms (100Hz) -- camera (actually runs 30fps
+//  20ms  (50Hz) -- update compass sensor
+//  50ms  (20Hz) -- create new log entry in log FIFO
+// 100ms  (10Hz) -- GPS update
+// 100ms  (10Hz) -- control update
+
+#define CTRL_SKIP 5
+#define MAG_SKIP 2
+#define LOG_SKIP 5
+
+int control_count=CTRL_SKIP;
+int update_count=MAG_SKIP;              // call Update_mag() every update_count calls to schedHandler()
+int log_count=LOG_SKIP;                 // buffer a new status entry for logging every log_count calls to schedHandler
+int tReal;                              // calculate real elapsed time
+
+// TODO: 3 better encapsulation, please
+extern Sensors sensors;
+extern SystemState state[SSBUF];
+extern unsigned char inState;
+extern unsigned char outState;
+extern bool ssBufOverrun;
+extern GPS gps;
+extern Mapping mapper;
+extern Steering steerCalc;              // steering calculator
+extern Timer timer;
+extern DigitalOut ahrsStatus;           // AHRS status LED
+
+// Navigation
+extern Config config;
+int nextWaypoint = 0;                   // next waypoint destination
+int lastWaypoint = 1;
+double bearing;                         // bearing to next waypoint
+double distance;                        // distance to next waypoint
+float steerAngle;                       // steering angle
+float cte;                              // Cross Track error
+float cteI;                             // Integral of Cross Track Error
+
+// Throttle PID
+float speedDt=0;                        // dt for the speed PID
+float integral=0;                       // error integral for speed PID
+float lastError=0;                      // previous error, used for calculating derivative
+bool go=false;                          // initiate throttle (or not)
+float desiredSpeed;                     // speed set point
+float nowSpeed;
+
+
+// Pose Estimation
+bool initNav = true;
+float initHdg = true;                   // indiciates that heading needs to be initialized by gps
+float initialHeading=-999;              // initial heading
+float myHeading=0;                      // heading sent to KF
+CartPosition cartHere;                  // position estimate, cartesian
+GeoPosition here;                       // position estimate, lat/lon
+extern GeoPosition gps_here;
+int timeZero=0;
+int lastTime=-1;                        // used to calculate dt for KF
+int thisTime;                           // used to calculate dt for KF
+float dt;                               // dt for the KF
+float lagHeading = 0;                   // lagged heading estimate
+//GeoPosition lagHere;                  // lagged position estimate; use here as the current position estimate
+float errAngle;                         // error between gyro hdg estimate and gps hdg estimate
+float gyroBias=0;                       // exponentially weighted moving average of gyro error
+float Ag = (2.0/(1000.0+1.0));          // Gyro bias filter alpha, gyro; # of 10ms steps
+float Kbias = 0.995;            
+float filtErrRate = 0;
+float biasErrAngle = 0;
+
+#define MAXHIST 128 // must be multiple of 0x08
+#define inc(x)  (x) = ((x)+1)&(MAXHIST-1)
+struct {
+    float x;        // x coordinate
+    float y;        // y coordinate
+    float hdg;      // heading
+    float dist;     // distance
+    float gyro;     // heading rate
+    float ghdg;     // uncorrected gyro heading
+    float dt;       // delta time
+} history[MAXHIST]; // fifo for sensor data, position, heading, dt
+
+int hCount=0;       // history counter; one > 100, we can go back in time to reference gyro history
+int now = 0;        // fifo input index
+int prev = 0;      // previous fifo iput index
+int lag = 0;        // fifo output index
+int lagPrev = 0;    // previous fifo output index
+
+
+/** set flag to initialize navigation at next schedHandler() call
+ */
+void restartNav()
+{
+    initNav = true;
+    initHdg = true;
+    return;
+}
+
+/** instruct the controller to throttle up
+ */
+void beginRun()
+{
+    go = true;
+    timeZero = thisTime; // initialize 
+    return;
+}
+
+void endRun()
+{
+    go = false;
+    initNav = true;
+    return;
+}
+
+/** get elasped time in update loop
+ */
+int getUpdateTime()
+{
+    return tReal;
+}
+
+void setSpeed(float speed) 
+{
+    if (desiredSpeed != speed) {
+        desiredSpeed = speed;
+        integral = 0;
+    }
+    return;
+}
+
+/** schedHandler fires off the various routines at appropriate schedules
+ *
+ */
+void update()
+{
+    tReal = timer.read_us();
+
+    ahrsStatus = 0;
+    thisTime = timer.read_ms();
+    dt = (lastTime < 0) ? 0 : ((float) thisTime - (float) lastTime) / 1000.0; // first pass let dt=0
+    lastTime = thisTime;
+
+    // Add up dt to speedDt
+    speedDt += dt;
+    
+    // Log Data Timestamp    
+    int timestamp = timer.read_ms();
+
+    //////////////////////////////////////////////////////////////////////////////
+    // NAVIGATION INIT
+    //////////////////////////////////////////////////////////////////////////////
+    // initNav is set with call to restartNav() when the "go" button is pressed.  Up
+    // to 10ms later this function is called and the code below will initialize the
+    // dead reckoning position and estimated position variables
+    // 
+    if (initNav == true) {
+        initNav = false;
+        here.set(config.wpt[0]);
+        nextWaypoint = 1; // Point to the next waypoint; 0th wpt is the starting point
+        lastWaypoint = 1; // Init to waypoint 1, we we don't start from wpt 0 at the turning speed
+        // Initialize lag estimates
+        //lagHere.set( here );
+        // Initialize fifo
+        hCount = 0;
+        now = 0;
+        // initialize what will become lag data in 1 second from now
+        history[now].dt = 0;
+        // initial position is waypoint 0
+        history[now].x = config.cwpt[0]._x;
+        history[now].y = config.cwpt[0]._y;
+        cartHere.set(history[now].x, history[now].y);
+        // initialize heading to bearing between waypoint 0 and 1
+        //history[now].hdg = here.bearingTo(config.wpt[nextWaypoint]);
+        history[now].hdg = cartHere.bearingTo(config.cwpt[nextWaypoint]);
+        history[now].ghdg = history[now].hdg;
+        initialHeading = history[now].hdg;
+        // Initialize Kalman Filter
+        headingKalmanInit(history[now].hdg);
+        // initialize cross track error
+        cte = 0;
+        cteI = 0;
+        // point next fifo input to slot 1, slot 0 occupied/initialized, now
+        lag = 0;
+        lagPrev = 0;
+        prev = now; // point to the most recently entered data
+        now = 1;    // new input slot
+    }
+
+
+    //////////////////////////////////////////////////////////////////////////////
+    // SENSOR UPDATES
+    //////////////////////////////////////////////////////////////////////////////
+
+    // TODO: 3 This really should run infrequently
+    sensors.Read_Power();
+
+    sensors.Read_Encoders(); 
+    nowSpeed = sensors.encSpeed;
+
+    sensors.Read_Gyro(); 
+
+    sensors.Read_Rangers();
+
+    //sensors.Read_Camera();
+
+    //////////////////////////////////////////////////////////////////////////////
+    // Obtain GPS data                        
+    //////////////////////////////////////////////////////////////////////////////
+
+    // synchronize when RMC and GGA sentences received w/ AHRS
+    // Do this in schedHandler??  GPS data is coming in not entirely in sync
+    // with the logging info
+    if (gps.nmea.rmc_ready() && gps.nmea.gga_ready()) {
+        char gpsdate[32], gpstime[32];
+
+        gps.process(gps_here, gpsdate, gpstime);
+        //gpsStatus = (gps.hdop > 0.0 && gps.hdop < 3.0) ? 1 : 0;
+
+        // update system status struct for logging
+        state[inState].gpsLatitude = gps_here.latitude();
+        state[inState].gpsLongitude = gps_here.longitude();
+        state[inState].gpsHDOP = gps.hdop;
+        state[inState].gpsCourse = gps.nmea.f_course();
+        state[inState].gpsSpeed = gps.nmea.f_speed_mph(); // can we just do kph/1000 ? or mps?
+        state[inState].gpsSats = gps.nmea.sat_count();
+    }
+    
+    //////////////////////////////////////////////////////////////////////////////
+    // HEADING AND POSITION UPDATE
+    //////////////////////////////////////////////////////////////////////////////
+
+    // TODO: 2 Position filtering
+    //    position will be updated based on heading error from heading estimate
+    // TODO: 2 Distance/speed filtering
+    //    this might be useful, but not sure it's worth the effort
+
+    // So the big pain in the ass is that the GPS data coming in represents the
+    // state of the system ~1s ago. Yes, a full second of lag despite running
+    // at 10hz (or whatever).  So if we try and fuse a lagged gps heading with a
+    // relatively current gyro heading rate, the gyro is ignored and the heading
+    // estimate lags reality
+    //
+    // In real life testing, the robot steering control was highly unstable with
+    // too much gain (typical of any negative feedback system with a very high
+    // phase shift and too much feedback). It'd drive around in circles trying to
+    // hunt for the next waypoint.  Dropping the gain restored stability but the
+    // steering overshot significantly, because of the lag.  It sort of worked but
+    // it was ugly. So here's my lame attempt to fix all this. 
+    // 
+    // We'll find out how much error there is between gps heading and the integrated
+    // gyro heading from a second ago.
+
+    // stick precalculated gyro data, with bias correction, into fifo
+    //history[now].gyro = sensors.gyro[_z_] - gyroBias;   
+    history[now].gyro = sensors.gyro[_z_];   
+
+    // Have to store dt history too (feh)
+    history[now].dt = dt;
+    
+    // Store distance travelled in a fifo for later use
+    history[now].dist = (sensors.lrEncDistance + sensors.rrEncDistance) / 2.0;
+
+
+    // Calc and store heading
+    history[now].ghdg = history[prev].ghdg + dt*history[now].gyro; // raw gyro calculated heading
+    //history[now].hdg = history[prev].ghdg - dt*gyroBias;           // bias-corrected gyro heading
+    history[now].hdg = history[prev].hdg + dt*history[now].gyro;
+    if (history[now].hdg >= 360.0) history[now].hdg -= 360.0;
+    if (history[now].hdg < 0)      history[now].hdg += 360.0;
+
+    //fprintf(stdout, "%d %d %.4f %.4f\n", now, prev, history[now].hdg, history[prev].hdg);
+
+    // We can't do anything until the history buffer is full
+    if (hCount < 100) {
+        // Until the fifo is full, only keep track of current gyro heading
+        hCount++; // after n iterations the fifo will be full
+    } else {
+        // Now that the buffer is full, we'll maintain a Kalman Filtered estimate that is
+        // time-shifted to the past because the GPS output represents the system state from
+        // the past. We'll also take our history of gyro readings from the most recent 
+        // filter update to the present time and update our current heading and position
+        
+        ////////////////////////////////////////////////////////////////////////////////
+        // UPDATE LAGGED ESTIMATE
+        
+        // Recover data from 1 second ago which will be used to generate
+        // updated lag estimates
+
+        // GPS heading is unavailable from this particular GPS at speeds < 0.5 mph
+        bool useGps = (state[inState].gpsLatitude != 0 &&
+                       state[inState].lrEncSpeed > 1.0 &&
+                       state[inState].rrEncSpeed > 1.0 &&
+                       (thisTime-timeZero) > 3000); // gps hdg converges by 3-5 sec.
+
+        // This represents the best estimate for heading... for one second ago
+        // If we do nothing else, the robot will think it is located at a position 1 second behind
+        // where it actually is. That means that any control feedback needs to have a longer time
+        // constant than 1 sec or the robot will have unstable heading correctoin.
+        // Use gps data when available, always use gyro data
+
+        // Clamp heading to initial heading when we're not moving; hopefully this will
+        // give the KF a head start figuring out how to deal with the gyro
+        if (go) {
+            lagHeading = headingKalman(history[lag].dt, state[inState].gpsCourse, useGps, history[lag].gyro, true);
+        } else {    
+            lagHeading = headingKalman(history[lag].dt, initialHeading, true, history[lag].gyro, true);
+        }
+
+        // TODO 1: need to figure out exactly how to update t-1 position correctly
+        // Update the lagged position estimate
+        //lagHere.move(lagHeading, history[lag].dist);
+        history[lag].x = history[lagPrev].x + history[lag].dist * sin(lagHeading);
+        history[lag].y = history[lagPrev].y + history[lag].dist * cos(lagHeading);
+        
+        ////////////////////////////////////////////////////////////////////////////////
+        // UPDATE CURRENT ESTIMATE
+       
+        // Now we need to re-calculate the current heading and position, starting with the most recent
+        // heading estimate representing the heading 1 second ago.
+        //        
+        // Nuance: lag and now have already been incremented so that works out beautifully for this loop
+        //
+        // Heading is easy. Original heading - estimated heading gives a tiny error. Add this to all the historical
+        // heading data up to present.
+        //
+        // For position re-calculation, we iterate 100 times up to present record. Haversine is way, way too slow,
+        // so is trig calcs is marginal. Update rate is 10ms and we can't hog more than maybe 2-3ms as the outer
+        // loop has logging work to do. Rotating each point is faster; pre-calculate sin/cos, etc.
+        //
+        // initialize these once
+        errAngle = (lagHeading - history[lag].hdg);
+        if (errAngle <= -180.0) errAngle += 360.0;
+        if (errAngle > 180) errAngle -= 360.0;
+
+        //fprintf(stdout, "%d %.2f, %.2f, %.4f %.4f\n", lag, lagHeading, history[lag].hdg, lagHeading - history[lag].hdg, errAngle);
+        float cosA = cos(errAngle * PI / 180);
+        float sinA = sin(errAngle * PI / 180);
+        // Start at the out side of the fifo which is from 1 second ago
+        int i = lag;
+        for (int j=0; j < 100; j++) {
+            history[i].hdg += errAngle;
+            // Rotate x, y by errAngle around pivot point; no need to rotate pivot point (j=0)
+            if (j > 0) {
+                float dx = history[i].x-history[lag].x;
+                float dy = history[i].y-history[lag].y;
+                history[i].x = history[lag].x + dx*cosA - dy*sinA;
+                history[i].y = history[lag].y + dx*sinA + dy*cosA;
+            }
+            inc(i);
+        }
+        
+        // gyro bias, correct only with shallow steering angles
+        // if we're not going, assume heading rate is 0 and correct accordingly
+        // If we are going, compare gyro-generated heading estimate with kalman
+        // heading estimate and correct bias accordingly using PI controller with
+        // fairly long time constant
+        // TODO: 3 Add something in here to stop updating if the gps is unreliable; need to find out what indicates poor gps heading
+        if (history[lag].dt > 0 && fabs(steerAngle) < 5.0 && useGps) {
+            biasErrAngle = Kbias*biasErrAngle + (1-Kbias)*(history[lag].ghdg - state[inState].gpsCourse); // can use this to compute gyro bias
+            if (biasErrAngle <= -180.0) biasErrAngle += 360.0;
+            if (biasErrAngle > 180) biasErrAngle -= 360.0;
+        
+            float errRate = biasErrAngle / history[lag].dt;
+
+            //if (!go) errRate = history[lag].gyro;
+
+            // Filter bias based on errRate which is based on filtered biasErrAngle
+            gyroBias = Kbias*gyroBias + (1-Kbias)*errRate;
+            //fprintf(stdout, "%d %.2f, %.2f, %.4f %.4f %.4f\n", lag, lagHeading, history[lag].hdg, errAngle, errRate, gyroBias);
+        }
+        
+        // make sure we update the lag heading with the new estimate
+        history[lag].hdg = lagHeading;
+        
+        // increment lag pointer and wrap        
+        lagPrev = lag;
+        inc(lag);
+        
+    }
+    state[inState].estHeading = history[lag].hdg;
+    // the variable "here" is the current position
+    //here.move(history[now].hdg, history[now].dist);
+    float r = PI/180 * history[now].hdg;
+    // update current position
+    history[now].x = history[prev].x + history[now].dist * sin(r);
+    history[now].y = history[prev].y + history[now].dist * cos(r);
+    cartHere.set(history[now].x, history[now].y);
+    mapper.cartToGeo(cartHere, &here);
+
+    // TODO: don't update gyro heading if speed ~0 -- or use this time to re-calc bias?
+    // (sensors.lrEncSpeed == 0 && sensors.rrEncSpeed == 0)
+
+    //////////////////////////////////////////////////////////////////////////////
+    // NAVIGATION UPDATE
+    //////////////////////////////////////////////////////////////////////////////
+    
+    //bearing = here.bearingTo(config.wpt[nextWaypoint]);
+    bearing = cartHere.bearingTo(config.cwpt[nextWaypoint]);
+    //distance = here.distanceTo(config.wpt[nextWaypoint]);
+    distance = cartHere.distanceTo(config.cwpt[nextWaypoint]);
+    //float prevDistance = here.distanceTo(config.wpt[lastWaypoint]);
+    float prevDistance = cartHere.distanceTo(config.cwpt[lastWaypoint]);
+    double relativeBrg = bearing - history[now].hdg;
+
+    // if correction angle is < -180, express as negative degree
+    // TODO: 3 turn this into a function
+    if (relativeBrg < -180.0) relativeBrg += 360.0;
+    if (relativeBrg > 180.0)  relativeBrg -= 360.0;
+
+    // if within config.waypointDist distance threshold move to next waypoint
+    // TODO: 3 figure out how to output feedback on wpt arrival external to this function
+    if (go) {
+
+        // if we're within brakeDist of next or previous waypoint, run @ turn speed
+        // This would normally mean we run at turn speed until we're brakeDist away
+        // from waypoint 0, but we trick the algorithm by initializing prevWaypoint to waypoint 1
+        if (distance < config.brakeDist || prevDistance < config.brakeDist) {
+            setSpeed( config.turnSpeed );
+        } else if ( (thisTime - timeZero) < 1000 ) {
+            setSpeed( config.startSpeed );
+        } else {
+            setSpeed( config.topSpeed );
+        }
+
+        if (distance < config.waypointDist) {
+            //fprintf(stdout, "Arrived at wpt %d\n", nextWaypoint);
+            //speaker.beep(3000.0, 0.5); // non-blocking
+            lastWaypoint = nextWaypoint;
+            nextWaypoint++;
+            cteI = 0;
+        }
+        
+    } else {
+        setSpeed( 0.0 );
+    }
+    // Are we at the last waypoint?
+    // currently handled external to this routine
+        
+    //////////////////////////////////////////////////////////////////////////////
+    // OBSTACLE DETECTION & AVOIDANCE
+    //////////////////////////////////////////////////////////////////////////////
+    // TODO: 1 limit steering angle based on object detection ?
+    // or limit relative brg perhaps?
+    // TODO: 1 add vision obstacle detection and filtering
+    // TODO: 1 add ranger obstacle detection and filtering/fusion with vision
+
+
+    //////////////////////////////////////////////////////////////////////////////
+    // CONTROL UPDATE
+    //////////////////////////////////////////////////////////////////////////////
+
+    if (--control_count == 0) {
+  
+        // Compute cross track error
+        cte = steerCalc.crossTrack(history[now].x, history[now].y,
+                                   config.cwpt[lastWaypoint]._x, config.cwpt[lastWaypoint]._y,
+                                   config.cwpt[nextWaypoint]._x, config.cwpt[nextWaypoint]._y);
+        cteI += cte;
+
+        // Use either pure pursuit algorithm or original algorithm  
+        if (config.usePP) {
+            steerAngle = steerCalc.purePursuitSA(state[inState].estHeading, 
+                                                 history[now].x, history[now].y,
+                                                 config.cwpt[lastWaypoint]._x, config.cwpt[lastWaypoint]._y,
+                                                 config.cwpt[nextWaypoint]._x, config.cwpt[nextWaypoint]._y);
+        } else {
+            steerAngle = steerCalc.calcSA(relativeBrg, config.minRadius); // use the configured minimum turn radius
+        }
+        
+        // Apply gain factor for near straight line
+        if (fabs(steerAngle) < config.steerGainAngle) steerAngle *= config.steerGain;
+
+        // Curb avoidance
+        if (sensors.rightRanger < config.curbThreshold) {
+            steerAngle -= config.curbGain * (config.curbThreshold - sensors.rightRanger);
+        }
+                    
+        setSteering( steerAngle );
+
+// void throttleUpdate( float speed, float dt )
+
+        // PID control for throttle
+        // TODO: 3 move all this PID crap into Actuators.cpp
+        // TODO: 3 probably should do KF or something for speed/dist; need to address GPS lag, too
+        // if nothing else, at least average the encoder speed over mult. samples
+        if (desiredSpeed <= 0.1) {
+            setThrottle( config.escZero );
+        } else {
+            // PID loop for throttle control
+            // http://www.codeproject.com/Articles/36459/PID-process-control-a-Cruise-Control-example
+            float error = desiredSpeed - nowSpeed; 
+            // track error over time, scaled to the timer interval
+            integral += (error * speedDt);
+            // determine the amount of change from the last time checked
+            float derivative = (error - lastError) / speedDt; 
+            // calculate how much to drive the output in order to get to the 
+            // desired setpoint. 
+            int output = config.escZero + (config.speedKp * error) + (config.speedKi * integral) + (config.speedKd * derivative);
+            if (output > config.escMax) output = config.escMax;
+            if (output < config.escMin) output = config.escMin;
+            //fprintf(stdout, "s=%.1f d=%.1f o=%d\n", nowSpeed, desiredSpeed, output);
+            setThrottle( output );
+            // remember the error for the next time around.
+            lastError = error; 
+        }
+
+        speedDt = 0; // reset dt to begin counting for next time
+        control_count = CTRL_SKIP;
+    }      
+
+    //////////////////////////////////////////////////////////////////////////////
+    // DATA FOR LOGGING
+    //////////////////////////////////////////////////////////////////////////////
+
+    // Periodically, we enter a new SystemState into the FIFO buffer
+    // The main loop handles logging and will catch up to us provided 
+    // we feed in new log entries slowly enough.
+    if (--log_count == 0) {
+        // Copy data into system state for logging
+        inState++;                      // Get next state struct in the buffer
+        inState &= SSBUF;               // Wrap around
+        ssBufOverrun = (inState == outState);
+        //
+        // Need to clear out encoder distance counters; these are incremented
+        // each time this routine is called.
+        state[inState].lrEncDistance = 0;
+        state[inState].rrEncDistance = 0;
+        //
+        // need to initialize gps data to be safe
+        //
+        state[inState].gpsLatitude = 0;
+        state[inState].gpsLongitude = 0;
+        state[inState].gpsHDOP = 0;
+        state[inState].gpsCourse = 0;
+        state[inState].gpsSpeed = 0;
+        state[inState].gpsSats = 0;
+        log_count = LOG_SKIP;       // reset counter
+    }
+
+    // Log Data Timestamp    
+    state[inState].millis = timestamp;
+    
+    // TODO: 3 recursive filtering on each of the state values
+    state[inState].voltage = sensors.voltage;
+    state[inState].current = sensors.current;
+    for (int i=0; i < 3; i++) {
+        state[inState].m[i] = sensors.m[i];
+        state[inState].g[i] = sensors.g[i];
+        state[inState].a[i] = sensors.a[i];
+    }
+    state[inState].gTemp = sensors.gTemp;
+    state[inState].gHeading = history[now].hdg;
+    state[inState].lrEncSpeed = sensors.lrEncSpeed;
+    state[inState].rrEncSpeed = sensors.rrEncSpeed;
+    state[inState].lrEncDistance += sensors.lrEncDistance;
+    state[inState].rrEncDistance += sensors.rrEncDistance;
+    //state[inState].encHeading += (state[inState].lrEncDistance - state[inState].rrEncDistance) / TRACK;
+    state[inState].estLatitude = here.latitude();
+    state[inState].estLongitude = here.longitude();
+    state[inState].estX = history[now].x;
+    state[inState].estY = history[now].y;
+    state[inState].bearing = bearing;
+    state[inState].distance = distance;
+    state[inState].nextWaypoint = nextWaypoint;
+    state[inState].gbias = gyroBias;
+    state[inState].errAngle = biasErrAngle;
+    state[inState].leftRanger = sensors.leftRanger;
+    state[inState].rightRanger = sensors.rightRanger;
+    state[inState].centerRanger = sensors.centerRanger;
+    state[inState].crossTrackErr = cte;
+    // Copy AHRS data into logging data
+    //state[inState].roll = ToDeg(ahrs.roll);
+    //state[inState].pitch = ToDeg(ahrs.pitch);
+    //state[inState].yaw = ToDeg(ahrs.yaw);
+
+    // increment fifo pointers with wrap-around
+    prev = now;
+    inc(now);
+
+    // timing
+    tReal = timer.read_us() - tReal;
+
+    ahrsStatus = 1;
+}
\ No newline at end of file
diff -r 000000000000 -r 826c6171fc1b updater.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/updater.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,23 @@
+#ifndef __SCHEDULER_H
+#define __SCHEDULER_H
+
+/** Updater is the main real time sensor update, estimation, and control routine that is
+ * called at 100Hz by a timer interrupt
+ */
+ 
+/** Returns the elapsed time taken by the updater routine on its most recent run */
+int getUpdateTime(void);
+
+/** Indicates to the updater that the vehicle should begin its run */
+void beginRun(void);
+
+/** Indicates to the updater that the vehicle should abort its run */
+void endRun(void);
+
+/** Tells the updater to re-initialize the navigation state */
+void restartNav(void);
+
+/** The function that is called at 100Hz. It reads sensors, performs estimation, and controls the robot */
+void update(void);
+
+#endif
diff -r 000000000000 -r 826c6171fc1b util.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/util.c	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,78 @@
+// convert character to an int
+//
+int ctoi(char c)
+{
+  int i=-1;
+  
+  if (c >= '0' && c <= '9') {
+    i = c - '0';
+  }
+
+  //printf("char: %c  int %d\n", c, i); 
+ 
+  return i;
+}
+
+
+// convert string to floating point
+//
+double cvstof(char *s)
+{
+  double f=0.0;
+  double mult = 0.1;
+  bool neg = false;
+  //char dec = 1;
+  
+  // leading spaces
+  while (*s == ' ' || *s == '\t') {
+    s++;
+    if (*s == 0) break;
+  }
+
+  // What about negative numbers?
+  if (*s == '-') {
+    neg = true;
+    s++;
+  }
+
+  // before the decimal
+  //
+  while (*s != 0) {
+    if (*s == '.') {
+      s++;
+      break;
+    }
+    f = (f * 10.0) + (double) ctoi(*s);
+    s++;
+  }
+  // after the decimal
+  while (*s != 0 && *s >= '0' && *s <= '9') {
+    f += (double) ctoi(*s) * mult;
+    mult /= 10;
+    s++;
+  }
+  
+  // if we were negative...
+  if (neg) f = -f;
+  
+  return f;
+}
+
+// copy t to s until delimiter is reached
+// return location of delimiter+1 in t
+// if s or t null, return null
+char *split(char *s, char *t, int max, char delim)
+{
+  int i = 0;
+  
+  if (s == 0 || t == 0)
+    return 0;
+
+  while (*t != 0 && *t != '\n' && *t != delim && i < max) {
+    *s++ = *t++;
+    i++;
+  }
+  *s = 0;
+    
+  return t+1;
+}
diff -r 000000000000 -r 826c6171fc1b util.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/util.h	Wed Jun 20 14:57:48 2012 +0000
@@ -0,0 +1,27 @@
+#ifndef __UTIL_H
+#define __UTIL_H
+
+/** Utility routines */
+
+#define clamp360(x) \
+                while ((x) >= 360.0) (x) -= 360.0; \
+                while ((x) < 0) (x) += 360.0;
+#define clamp180(x) ((x) - floor((x)/360.0) * 360.0 - 180.0);
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+/** Convert char to integer */
+int ctoi(char c);
+/** Convert string to floating point */
+double cvstof(char *s);
+/** Tokenize a string 
+ * @param s is the string to tokenize
+ * @param max is the maximum number of characters
+ * @param delim is the character delimiter on which to tokenize
+ * @returns t is the pointer to the next token
+ */
+char *split(char *s, char *t, int max, char delim);
+
+#endif
\ No newline at end of file