diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h
index 18b5794ca717d6b5cc1e6015c8608ff5ee1b7329..36e10ac9d19d60833e47159808076ad82e63ed42 100644
--- a/ArduPlane/APM_Config.h
+++ b/ArduPlane/APM_Config.h
@@ -28,3 +28,6 @@
 
 */
 
+// use this to enable the new MAVLink 1.0 protocol, instead of the
+// older 0.9 protocol
+// #define MAVLINK10 ENABLED
diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 7740128199c7ad9c6b3ccf411a93daa80dc1aca8..fcf4af17bf4f152444315a572ce67f839d578158 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -47,13 +47,14 @@ version 2.1 of the License, or (at your option) any later version.
 #include <Filter.h>			// Filter library
 #include <ModeFilter.h>		// Mode Filter from Filter library
 #include <AP_Relay.h>       // APM relay
-#include <AP_Mount.h>		// Camera/Antenna mount
-#include <GCS_MAVLink.h>    // MAVLink GCS definitions
 #include <memcheck.h>
 
 // Configuration
 #include "config.h"
 
+#include <GCS_MAVLink.h>    // MAVLink GCS definitions
+#include <AP_Mount.h>		// Camera/Antenna mount
+
 // Local modules
 #include "defines.h"
 #include "Parameters.h"
diff --git a/ArduPlane/GCS.h b/ArduPlane/GCS.h
index 607fe197dd03b4590b11b3d65bf26a8621ca9c9b..c10a7e0d670f6620d47ed5e470c19e7baa3aef7a 100644
--- a/ArduPlane/GCS.h
+++ b/ArduPlane/GCS.h
@@ -8,7 +8,6 @@
 
 #include <FastSerial.h>
 #include <AP_Common.h>
-#include <GCS_MAVLink.h>
 #include <GPS.h>
 #include <Stream.h>
 #include <stdint.h>
diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde
index 5cd4841ddc37846ec71bf6c56a087319b6829c8d..c1313c37ba9ae53ebd6925fd91ccad73caf677ea 100644
--- a/ArduPlane/GCS_Mavlink.pde
+++ b/ArduPlane/GCS_Mavlink.pde
@@ -27,7 +27,7 @@ static bool mavlink_active;
 
 static NOINLINE void send_heartbeat(mavlink_channel_t chan)
 {
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
     uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
     uint8_t system_status = MAV_STATE_ACTIVE;
     uint32_t custom_mode = control_mode;
@@ -130,7 +130,7 @@ static NOINLINE void send_fence_status(mavlink_channel_t chan)
 
 static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
 {
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
     uint32_t control_sensors_present = 0;
     uint32_t control_sensors_enabled;
     uint32_t control_sensors_health;
@@ -337,7 +337,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
 
 static void NOINLINE send_gps_raw(mavlink_channel_t chan)
 {
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
     uint8_t fix = g_gps->status();
     if (fix == GPS::GPS_OK) {
         fix = 3;
@@ -501,6 +501,21 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
 #endif // HIL_MODE != HIL_MODE_ATTITUDE
 
 #ifdef DESKTOP_BUILD
+void mavlink_simstate_send(uint8_t chan,
+                           float roll,
+                           float pitch,
+                           float yaw,
+                           float xAcc,
+                           float yAcc,
+                           float zAcc,
+                           float p,
+                           float q,
+                           float r)
+{
+    mavlink_msg_simstate_send((mavlink_channel_t)chan,
+                              roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
+}
+
 // report simulator state
 static void NOINLINE send_simstate(mavlink_channel_t chan)
 {
@@ -592,7 +607,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
         break;
 
     case MSG_GPS_RAW:
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
         CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
 #else
         CHECK_PAYLOAD_SIZE(GPS_RAW);
@@ -1082,7 +1097,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             break;
         }
 
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
     case MAVLINK_MSG_ID_COMMAND_LONG:
         {
             // decode
@@ -1272,7 +1287,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             mavlink_set_mode_t packet;
             mavlink_msg_set_mode_decode(msg, &packet);
 
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
             if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
                 // we ignore base_mode as there is no sane way to map
                 // from that bitmap to a APM flight mode. We rely on
@@ -1328,7 +1343,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             break;
 		}
 
-#ifndef MAVLINK10
+#if MAVLINK10 == DISABLED
     case MAVLINK_MSG_ID_SET_NAV_MODE:
 		{
             // decode
@@ -1680,7 +1695,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
                 break;
 
             default:
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
                 result = MAV_MISSION_UNSUPPORTED;
 #endif
                 break;
@@ -1896,7 +1911,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
 	#if HIL_MODE != HIL_MODE_DISABLED
         // This is used both as a sensor and to pass the location
         // in HIL_ATTITUDE mode.
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
 	case MAVLINK_MSG_ID_GPS_RAW_INT:
         {
             // decode
@@ -1934,7 +1949,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             airspeed = 100*packet.airspeed;
             break;
         }
-#ifdef MAVLINK10
+#if MAVLINK10 == ENABLED
 	case MAVLINK_MSG_ID_HIL_STATE:
 		{
 			mavlink_hil_state_t packet;
@@ -2257,3 +2272,19 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
         mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
     }
 }
+
+// this code was moved from libraries/GCS_MAVLink to allow compile
+// time selection of MAVLink 1.0
+BetterStream	*mavlink_comm_0_port;
+BetterStream	*mavlink_comm_1_port;
+
+mavlink_system_t mavlink_system = {7,1,0,0};
+
+uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
+{
+    if (sysid != mavlink_system.sysid)
+        return 1;
+    // Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
+    // If it is addressed to our system ID we assume it is for us
+    return 0; // no error
+}
diff --git a/ArduPlane/Makefile b/ArduPlane/Makefile
index 8f7c0a9050c6320c0afda48612684c6d6365934b..d8ed558b997538b878f88c337ec8ba03cd12268b 100644
--- a/ArduPlane/Makefile
+++ b/ArduPlane/Makefile
@@ -25,13 +25,13 @@ apm2beta:
 	make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DAPM2_BETA_HARDWARE"
 
 mavlink10:
-	make -f Makefile EXTRAFLAGS="-DMAVLINK10"
+	make -f Makefile EXTRAFLAGS="-DMAVLINK10=1"
 
 sitl:
 	make -f ../libraries/Desktop/Makefile.desktop
 
 sitl-mavlink10:
-	make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10"
+	make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10=1"
 
 sitl-mount:
 	make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMOUNT=ENABLED"
diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h
index 9144bf3cfdd05c9800c8ade252f22d79fca02d7a..f88576b2b8daca3b119c2c60d17b7914c5af7222 100644
--- a/ArduPlane/defines.h
+++ b/ArduPlane/defines.h
@@ -95,8 +95,6 @@
 #define RELAY_TOGGLE 5
 #define STOP_REPEAT 10
 
-#define MAV_CMD_CONDITION_YAW 23
-
 //  GCS Message ID's
 /// NOTE: to ensure we never block on sending MAVLink messages
 /// please keep each MSG_ to a single MAVLink message. If need be